simulation.utils.ros_base package

Submodules

simulation.utils.ros_base.node_base module

ROS node base class with a pythonic parameter interface.

Classes:

NodeBase(*, name, parameter_cache_time, …)

Abstract ROS Node class with additional functionality.

ParameterObject(*, ns, set_param_func, Any], …)

ROS parameter wrapper to recursively get and set parameters.

class NodeBase(*, name: str, parameter_cache_time: float = 1, log_level: int = 2)[source]

Bases: object

Abstract 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

ParameterObject

Methods:

_get_param(key)

Get (possibly) cached ROS parameter.

_set_param(key, value)

Set ROS parameter.

run(*[, function, rate])

Helper function, starting the node and shutting it down once ROS signals to.

start()

Called when activating the node.

stop()

Called when deactivating or shutting down the node.

__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 rate when node is active

start()[source]

Called when activating the node.

stop()[source]

Called when deactivating or shutting down the node.

class ParameterObject(*, ns: str, set_param_func: Callable[[str, Any], None], get_param_func: Callable[[str], Any])[source]

Bases: object

ROS 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]

Methods:

as_dict()

Return all parameters in current namespace as dicts.

as_dict()Dict[str, Any][source]

Return all parameters in current namespace as dicts.

simulation.utils.ros_base.transform_node module

ROS transform base node class with tf2 transform interface.

Classes:

TransformNode(*, name, parameter_cache_time, …)

Extends NodeBase with a tf2 transform handler.

class TransformNode(*, name: str, parameter_cache_time: float = 1, log_level: int = 2)[source]

Bases: simulation.utils.ros_base.node_base.NodeBase

Extends NodeBase with a tf2 transform handler.

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.

Methods:

get_transformation(target_frame, …[, timeout])

tf2 transform handler.

get_transformation(target_frame: str, source_frame: str, timestamp: rospy.rostime.Time, timeout: rospy.rostime.Duration = rospy.Duration[100000000])Optional[simulation.utils.geometry.transform.Transform][source]

tf2 transform handler.

Parameters
  • target_frame (str) – Name of the target frame

  • source_frame (str) – Name of the source frame

  • timestamp (rospy.rostime.Time) – The time in the buffer

  • timeout (rospy.rostime.Duration) – Lookup timeout

Returns

Returns the transformation.

simulation.utils.ros_base.visualization module

Utility functions for visualizing ROS messages in rviz.

Functions:

get_marker(frame_id[, type, rgba, id, ns, …])

Create a rviz marker message.

get_marker_for_points(points, *, frame_id[, …])

Rviz marker message from a list of points.

get_marker(frame_id: str, type: int = 4, rgba: List[float] = [0, 0, 0, 1], id: int = 0, ns: Optional[str] = None, duration: float = 1, scale: float = 0.02)[source]

Create a rviz marker message. The position or points can be added.

Parameters
  • frame_id – Name of the points’ coordinate frame (e.g. world, vehicle, simulation)

  • type – Rviz marker type

  • rgba – Color of the marker

  • id – Marker id

  • ns – Rviz namespace

  • duration – Marker will be shown for this long

Returns

Marker msg that rviz can display

get_marker_for_points(points: List[simulation.utils.geometry.point.Point], *, frame_id: str, type: int = 4, rgba: List[float] = [0, 0, 0, 1], id: int = 0, ns: Optional[str] = None, duration: float = 1, scale: float = 0.02)visualization_msgs.msg._Marker.Marker[source]

Rviz marker message from a list of points.

Parameters
  • points – Points to visualize

  • frame_id – Name of the points’ coordinate frame (e.g. world, vehicle, simulation)

  • type – Rviz marker type

  • rgba – Color of the marker

  • id – Marker id

  • ns – Rviz namespace

  • duration – Marker will be shown for this long

Returns

Marker msg that rviz can display

Module contents