simulation.utils.ros_base.node_base module¶
ROS node base class with a pythonic parameter interface.
Summary¶
Classes:
Abstract ROS Node class with additional functionality. |
|
ROS parameter wrapper to recursively get and set parameters. |
Reference¶
-
class
NodeBase(*, name: str, parameter_cache_time: float = 1, log_level: int = 2)[source]¶ Bases:
objectAbstract ROS Node class with additional functionality.
- Parameters
name (str) – Name of the node
parameter_cache_time (int) – Duration for which parameters will be cached for performance
log_level (int) – Loglevel with which the node works.
A basic node with a subscriber and publisher can be created in the following way:
>>> from simulation.utils.ros_base.node_base import NodeBase >>> class NodeSubClass(NodeBase): ... def __init__(self): ... super(NodeSubClass,self).__init__("node_name") # Important! ... # ... ... self.run() # Calls .start() if self.param.active is True (default: True) ... def start(self): ... # self.subscriber = ... ... # self.publisher = ... ... super().start() # Make sure to call this! ... # Called when deactivating the node by setting self.param.active to false ... # E.g. through command line with: rosparam set .../node/active false ... # or when ROS is shutting down ... def stop(self): ... # self.subscriber.unregister() ... # self.publisher.unregister() ... super().stop() # Make sure to call this!
-
param¶ Attribute of type
ParameterObject, which provides an abstraction layer to access ROS parameters. The following line shows how to access a ROS parameter in any subclass of called param_1:>>> self.param.param_1 'value_1'
This is equivalent to:
>>> rospy.get_param('~param_1') 'value_1'
Setting a parameter is equally easy:
>>> self.param.param_2 = 'value_2'
This is equivalent to:
>>> rospy.set_param('~param_2', 'value_2')
The magic begins when parameters are defined in a hierarchical structure. After starting a node with the following YAML parameter file:
car: name: 'dr_drift' size: length: 0.6 width: 0.4 ...
the cars dimensions can be retrieved just like any other python attribute:
>>> self.param.car.size.length 0.6
and changes are also synchronized with ROS:
>>> rospy.get_param("~car/name") 'dr_drift' >>> self.param.car.name = 'captain_rapid' >>> rospy.get_param("~car/name") 'captain_rapid'
- Type
-
__shutdown()¶ Called when ROS is shutting down.
If the node was active before, self.stop is called.
-
_get_param(key: str) → Any[source]¶ Get (possibly) cached ROS parameter.
- Parameters
key (str) – Name of the ROS parameter
- Returns
If the parameter is in the parameter cache, the cached value is returned. Otherwise rospy.get_param(key) is returned.
-
_set_param(key: str, value: Any)[source]¶ Set ROS parameter. Also the parameter cache is cleared, to prevent incoherence.
- Parameters
key (str) – Name of the ROS parameter
value (Any) – New value
-
run(*, function: Optional[Callable] = None, rate: float = 1)[source]¶ Helper function, starting the node and shutting it down once ROS signals to. Can only be called if the subclass implements start and stop functions.
- Parameters
rate (float) – Rate with which to update active/ not active status of the node
function – Called with a frequency of
ratewhen node is active
-
class
ParameterObject(*, ns: str, set_param_func: Callable[[str, Any], None], get_param_func: Callable[[str], Any])[source]¶ Bases:
objectROS parameter wrapper to recursively get and set parameters.
This class enables to access nested parameters within nodes. For example in any subclass of NodeBase one can call nested parameters (if they are defined!) in the following way:
>>> self.param.dict_of_parameters.key
Which is the same as calling:
>>> rospy.get_param("~dict_of_parameters/key")
This is achieved by overriding the __getattr__ and __setattr__ functions and passing calls through to the
- Parameters
ns – Namespace this parameter dictionary operates in
set_param_func – Callable object which gets called when a parameter is set
get_param_func – Callable object which gets called when a parameter is accessed
-
_ns¶ Namespace of this object
- Type
str
-
_set_param¶ Called when a new parameter should be set
- Type
Callable[[str, Any], None]
-
_get_param¶ Called when a parameter is requested
- Type
Callable[[str], Any]