rosros 0.2.5
Simple unified interface to ROS1 / ROS2 Python API
Loading...
Searching...
No Matches
rosros.ros2 Namespace Reference

ROS2 core interface. More...

Classes

class  Bag
 ROS2 bag interface, partially mimicking rosbag.Bag. More...
 
class  Mutex
 Container for local mutexes. More...
 
class  ROSLogHandler
 Logging handler that forwards logging messages to ROS2 logger. More...
 

Functions

 _assert_node ()
 Raises if ROS2 node not inited.
 
 _get_message_type_hash (typename)
 Returns ROS2 message type MD5 hash (internal caching method).
 
 _resolve_name (name, namespace=None)
 Returns absolute name, namespaced under current node if relative or private.
 
 canonical (typename)
 Returns "pkg/Type" for "pkg/msg/Type", standardizes various ROS2 formats.
 
 create_client (service, cls_or_typename, **qosargs)
 Returns a ROS2 service client instance, for invoking a service.
 
 create_publisher (topic, cls_or_typename, latch=False, queue_size=0, **qosargs)
 Returns a ROS2 publisher instance.
 
 create_rate (frequency)
 Returns a ROS2 rate instance, for sleeping at a fixed rate.
 
 create_service (service, cls_or_typename, callback, **qosargs)
 Returns a ROS2 service server instance, for providing a service.
 
 create_subscriber (topic, cls_or_typename, callback, callback_args=None, queue_size=0, raw=False, **qosargs)
 Returns a ROS2 subscriber instance.
 
 create_timer (period, callback, oneshot=False, immediate=False)
 Returns a ROS2 timer instance.
 
 delete_param (name)
 Deletes parameter from the node.
 
 deserialize_message (raw, cls_or_typename)
 Returns ROS2 message or service request/response instantiated from serialized binary.
 
 destroy_entity (item)
 Closes the given publisher, subscriber, service client, service server, timer, or rate instance.
 
 format_param_name (name)
 Returns parameter name using "." separator, and leading root or private sigils stripped.
 
 get_logger ()
 Returns `logging.Logger` for logging to ROS2 log handler.
 
 get_message_class (msg_or_type)
 Returns ROS2 message / service class object.
 
 get_message_definition (msg_or_type, full=True)
 Returns ROS2 message or service request/response type definition text.
 
 get_message_fields (val)
 Returns {field name: field type name} if ROS2 message or service request/response, else {}.
 
 get_message_header (val)
 Returns message `std_msgs/Header`-attribute if any, else `None`.
 
 get_message_type (msg_or_cls)
 Returns ROS2 message / service canonical type name, like "std_msgs/Header".
 
 get_message_type_hash (msg_or_type)
 Returns ROS2 message / service type MD5 hash.
 
 get_message_value (msg, name, default=...)
 Returns object attribute value, with numeric arrays converted to lists.
 
 get_namespace ()
 Returns ROS2 node namespace.
 
 get_node_name ()
 Returns ROS2 node full name with namespace.
 
 get_nodes ()
 Returns all ROS2 nodes, as `[node full name, ]`.
 
 get_package_share_directory (name)
 Returns the share directory of the package.
 
 get_param (name, default=None, autoset=True)
 Returns parameter value from current ROS2 node.
 
 get_param_names ()
 Returns the names of all current ROS2 node parameters.
 
 get_params (nested=True)
 Returns the current ROS2 node parameters, by default as nested dictionary.
 
 get_rostime ()
 Returns current ROS2 time, as `rclpy.time.Time`.
 
 get_service_definition (srv_or_type)
 Returns ROS2 service type definition text.
 
 get_service_request_class (srv_or_type)
 Returns ROS2 service request class object.
 
 get_service_response_class (srv_or_type)
 Returns ROS2 service response class object.
 
 get_services (node=None, namespace=None, include_types=True)
 Returns all available ROS2 services, as `[(service name, [type name, ]), ]`.
 
 get_topic_qos (topic, cls_or_typename, queue_size=10, publish=False)
 Returns dictionary for populating rclpy.qos.QoSProfile compatible with counterparts on topic.
 
 get_topics ()
 Returns all available ROS2 topics, as `[(topic name, [type name, ]), ]`.
 
 has_param (name)
 Returns whether the parameter exists.
 
 init_node (name, args=None, namespace=None, anonymous=False, log_level=None, enable_rosout=True, multithreaded=True, reentrant=False)
 Initializes rclpy and creates ROS2 node.
 
 init_params (defaults=None, **defaultkws)
 Declares all parameters on node from defaults dictionary.
 
 is_ros_message (val)
 Returns whether value is a ROS2 message or service request/response class or instance.
 
 is_ros_service (val)
 Returns whether value is a ROS2 service class object.
 
 is_ros_time (val)
 Returns whether value is a ROS2 time/duration class or instance.
 
 make_duration (secs=0, nsecs=0)
 Returns an rclpy.duration.Duration.
 
 make_time (secs=0, nsecs=0)
 Returns a ROS2 time, as rclpy.time.Time.
 
 ok ()
 Returns whether ROS2 has been initialized and is not shut down.
 
 on_shutdown (callback, *args, **kwargs)
 Registers function to be called on shutdown, after node has been torn down.
 
 register_init (node)
 Informs `rosros` of ROS2 having been initialized outside of `init_node()`.
 
 remap_name (name, namespace=None)
 Returns the absolute remapped topic/service name if mapping exists.
 
 resolve_name (name, namespace=None)
 Returns absolute remapped name, namespaced under current node if relative or private.
 
 scalar (typename)
 Returns unbounded scalar type from ROS2 message data type.
 
 serialize_message (msg)
 Returns ROS2 message or service request/response as a serialized binary of `bytes()`.
 
 set_param (name, value, descriptor=None)
 Sets a parameter on the node, auto-declaring it if unknown so far.
 
 shutdown (reason=None)
 Shuts down ROS2 execution, if any.
 
 sleep (duration)
 Sleeps for the specified duration in ROS time.
 
 spin ()
 Spins ROS2 node forever.
 
 spin_once (timeout=None)
 Executes one pending ROS2 operation or waits until timeout.
 
 spin_until_future_complete (future, timeout=None)
 Spins ROS2 until future complete or timeout reached or ROS shut down.
 
 start_spin ()
 Sets ROS2 node spinning forever in a background thread.
 
 time_message (val, to_message=True, clock_type=None)
 Converts ROS2 time/duration between `rclpy` and `builtin_interfaces` objects.
 
 to_duration (val)
 Returns value as ROS2 duration if convertible (int/float/time/datetime/decimal), else value.
 
 to_nsec (val)
 Returns value in nanoseconds if value is ROS2 time/duration, else value.
 
 to_sec (val)
 Returns value in seconds if value is ROS2 time/duration, else value.
 
 to_sec_nsec (val)
 Returns value as (seconds, nanoseconds) if value is ROS2 time/duration, else value.
 
 to_time (val)
 Returns value as ROS2 time if convertible, else value.
 
 wait_for_publisher (topic, timeout=None, cls_or_typename=None)
 Blocks until topic has at least one publisher.
 
 wait_for_service (service, timeout=None, cls_or_typename=None)
 Blocks until service is available.
 
 wait_for_subscriber (topic, timeout=None, cls_or_typename=None)
 Blocks until topic has at least one subscriber.
 

Variables

 AnyMsg = patch.AnyMsg
 Stand-in for `rospy.AnyMsg` with equivalent interface.
 
 args
 
 CALLBACK_GROUP = None
 `rclpy.callback_groups.CallbackGroup` instance
 
 called
 
dict DDS_TYPES
 Data Distribution Service types to ROS builtins.
 
 EXECUTOR = None
 `rclpy.executors.Executor` instance
 
str FAMILY = "rclpy"
 ROS Python module family, "rclpy".
 
 func
 
 kwargs
 
 NODE = None
 `rclpy.node.Node` instance
 
str PARAM_SEPARATOR = "."
 Separator char between ROS2 parameter namespace parts.
 
str PRIVATE_PREFIX = "~"
 Prefix for "private" names, auto-namespaced under current namespace.
 
dict ROS_ALIAS_TYPES = {"byte": "uint8", "char": "int8"}
 Mapping between ROS type aliases and real types, like {"byte": "uint8"}.
 
dict ROS_TIME_CLASSES
 ROS2 time/duration types and message types mapped to type names.
 
dict ROS_TIME_MESSAGES
 ROS2 time/duration types mapped to message types.
 
list ROS_TIME_TYPES = ["builtin_interfaces/Time", "builtin_interfaces/Duration"]
 ROS2 time/duration message types.
 
bool SHUTDOWN = False
 Flag for `shutdown()` been called.
 
list SHUTDOWN_CALLBACKS = []
 Callbacks registered with on_shutdown()
 
 SPINNER = None
 `threading.Thread` running `EXECUTOR.spin()`
 

Detailed Description

ROS2 core interface.

Function Documentation

◆ _assert_node()

rosros.ros2._assert_node ( )
protected

Raises if ROS2 node not inited.

Definition at line 594 of file ros2.py.

◆ _get_message_type_hash()

rosros.ros2._get_message_type_hash (   typename)
protected

Returns ROS2 message type MD5 hash (internal caching method).

Definition at line 1437 of file ros2.py.

◆ _resolve_name()

rosros.ros2._resolve_name (   name,
  namespace = None 
)
protected

Returns absolute name, namespaced under current node if relative or private.

Parameters
namespacenamespace to use if not current node full name

Definition at line 1177 of file ros2.py.

◆ canonical()

rosros.ros2.canonical (   typename)

Returns "pkg/Type" for "pkg/msg/Type", standardizes various ROS2 formats.

Converts DDS types like "octet" to "byte", and "sequence<uint8, 100>" to "uint8[100]".

Definition at line 1286 of file ros2.py.

◆ create_client()

rosros.ros2.create_client (   service,
  cls_or_typename,
**  qosargs 
)

Returns a ROS2 service client instance, for invoking a service.

Parameters
servicename of service to invoke
cls_or_typenameROS2 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool"
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability`
Returns
`rclpy.client.Client`, will support keyword arguments in calls and be callable itself

Definition at line 921 of file ros2.py.

◆ create_publisher()

rosros.ros2.create_publisher (   topic,
  cls_or_typename,
  latch = False,
  queue_size = 0,
**  qosargs 
)

Returns a ROS2 publisher instance.

Parameters
topicname of topic to open
cls_or_typenameROS2 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
latchprovide last published message to new subscribers (sets `DurabilityPolicy.TRANSIENT_LOCAL`)
queue_sizequeue size of outgoing messages (0 or None: infinite)
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability`
Returns
`rclpy.publisher.Publisher`, will support keyword arguments in `publish()` and have `get_num_connections()`

Definition at line 967 of file ros2.py.

◆ create_rate()

rosros.ros2.create_rate (   frequency)

Returns a ROS2 rate instance, for sleeping at a fixed rate.

Parameters
frequencyrate to sleep at, in Hz
Returns
`rclpy.timer.Rate`

Definition at line 1039 of file ros2.py.

◆ create_service()

rosros.ros2.create_service (   service,
  cls_or_typename,
  callback,
**  qosargs 
)

Returns a ROS2 service server instance, for providing a service.

Parameters
servicename of service to provide
cls_or_typenameROS2 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool"
callbackcallback function, invoked with `(request, response)`, expected to return the populated response, or a list/tuple/dictionary for populating the response. If the function only takes one argument, it is invoked with `(request)`.
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability`
Returns
`rclpy.service.Service`

Definition at line 944 of file ros2.py.

◆ create_subscriber()

rosros.ros2.create_subscriber (   topic,
  cls_or_typename,
  callback,
  callback_args = None,
  queue_size = 0,
  raw = False,
**  qosargs 
)

Returns a ROS2 subscriber instance.

Parameters
topicname of topic to listen to
cls_or_typenameROS2 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
callbackcallback function, invoked with received message, and with additional arguments if given
callback_argsadditional arguments to pass to the callback, if any, invoked as `callback(msg, callback_args)´
queue_sizequeue size of incoming messages (0 or None: infinite)
rawinvoke callback with serialized message bytes
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability`. `__autodetect` will look up current publishers on the topic and create a compatible QoS.
Returns
`rclpy.subscription.Subscription`

Definition at line 993 of file ros2.py.

◆ create_timer()

rosros.ros2.create_timer (   period,
  callback,
  oneshot = False,
  immediate = False 
)

Returns a ROS2 timer instance.

Parameters
perioddesired period between callbacks, as seconds or ROS duration
callbackcallback function invoked on timer, with no arguments
oneshotwhether to fire only once
immediatewhether to fire once immediately instead of waiting one period
Returns
`rclpy.timer.Timer`

Definition at line 1016 of file ros2.py.

◆ delete_param()

rosros.ros2.delete_param (   name)

Deletes parameter from the node.

Parameters
namefull name of the parameter in node namespace
Exceptions
KeyErrorif parameter not set

Definition at line 765 of file ros2.py.

◆ deserialize_message()

rosros.ros2.deserialize_message (   raw,
  cls_or_typename 
)

Returns ROS2 message or service request/response instantiated from serialized binary.

Definition at line 1556 of file ros2.py.

◆ destroy_entity()

rosros.ros2.destroy_entity (   item)

Closes the given publisher, subscriber, service client, service server, timer, or rate instance.

Definition at line 1044 of file ros2.py.

◆ format_param_name()

rosros.ros2.format_param_name (   name)

Returns parameter name using "." separator, and leading root or private sigils stripped.

Definition at line 1318 of file ros2.py.

◆ get_logger()

rosros.ros2.get_logger ( )

Returns `logging.Logger` for logging to ROS2 log handler.

Logging methods on the logger (`debug()`, `info()`, etc) accept additional keyword arguments:

  • `__once__`: whether to log only once from call site
  • `__throttle__`: seconds to skip logging from call site for
  • `__throttle_identical__`: whether to skip logging identical consecutive texts from call site (given log message excluding formatting arguments). Combines with `__throttle__` to skip duplicates for a period.

Definition at line 1133 of file ros2.py.

◆ get_message_class()

rosros.ros2.get_message_class (   msg_or_type)

Returns ROS2 message / service class object.

Parameters
msg_or_typefull or canonical class name, like "std_msgs/Bool" or "std_srvs/SetBool" or "std_srvs/SetBoolRequest"; or class instance like `std_msgs.msg.Bool()`
Returns
ROS2 message / service class object, like `std_msgs.msg.Bool` or `std_srvs.srv.SetBool` or `std_srvs.srv.SetBoolRequest`, or None if not found

Definition at line 1332 of file ros2.py.

◆ get_message_definition()

rosros.ros2.get_message_definition (   msg_or_type,
  full = True 
)

Returns ROS2 message or service request/response type definition text.

Text will include subtype definitions by default for messages.

Parameters
msg_or_typecanonical or full class name like "std_msgs/Bool" or "std_msgs/msg/Bool", or class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`
fullinclude definitions of nested types, separated by "\n---\nMSG: pkg/Type\n" (ignored for service request/response types)
Returns
message type definition text

Definition at line 1364 of file ros2.py.

◆ get_message_fields()

rosros.ros2.get_message_fields (   val)

Returns {field name: field type name} if ROS2 message or service request/response, else {}.

Parameters
valROS2 message or service request/response instance, or class object

Definition at line 1388 of file ros2.py.

◆ get_message_header()

rosros.ros2.get_message_header (   val)

Returns message `std_msgs/Header`-attribute if any, else `None`.

Parameters
valROS message or service request/response instance

Definition at line 1398 of file ros2.py.

◆ get_message_type()

rosros.ros2.get_message_type (   msg_or_cls)

Returns ROS2 message / service canonical type name, like "std_msgs/Header".

Returns "*" for `AnyMsg`.

Parameters
msg_or_clsclass instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`
Returns
canonical name, or `None` if not ROS message / service

Definition at line 1414 of file ros2.py.

◆ get_message_type_hash()

rosros.ros2.get_message_type_hash (   msg_or_type)

Returns ROS2 message / service type MD5 hash.

Parameters
msg_or_typefull or canonical class name like "std_msgs/Bool" or "std_srvs/SetBool" or "std_srvs/SetBoolRequest", or class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`

Definition at line 1428 of file ros2.py.

◆ get_message_value()

rosros.ros2.get_message_value (   msg,
  name,
  default = ... 
)

Returns object attribute value, with numeric arrays converted to lists.

Parameters
namemessage attribute name; may also be (nested, path) or "nested.path"
defaultvalue to return if attribute does not exist; raises exception otherwise

Definition at line 1448 of file ros2.py.

◆ get_namespace()

rosros.ros2.get_namespace ( )

Returns ROS2 node namespace.

Definition at line 1060 of file ros2.py.

◆ get_node_name()

rosros.ros2.get_node_name ( )

Returns ROS2 node full name with namespace.

Definition at line 1066 of file ros2.py.

◆ get_nodes()

rosros.ros2.get_nodes ( )

Returns all ROS2 nodes, as `[node full name, ]`.

Definition at line 1072 of file ros2.py.

◆ get_package_share_directory()

rosros.ros2.get_package_share_directory (   name)

Returns the share directory of the package.

For example, "/opt/ros/foxy/share/name" or "/home/ros1_ws/install/share/name".

Exceptions
KeyErrorif package not found

Definition at line 1475 of file ros2.py.

◆ get_param()

rosros.ros2.get_param (   name,
  default = None,
  autoset = True 
)

Returns parameter value from current ROS2 node.

Parameters
defaultoptional default to return if parameter unknown
autosetset default value to node parameter if unknown
Returns
parameter value, or default if parameter was unknown
Exceptions
KeyErrorif parameter not set and default not given

Definition at line 712 of file ros2.py.

◆ get_param_names()

rosros.ros2.get_param_names ( )

Returns the names of all current ROS2 node parameters.

Definition at line 722 of file ros2.py.

◆ get_params()

rosros.ros2.get_params (   nested = True)

Returns the current ROS2 node parameters, by default as nested dictionary.

Parameters
nestedreturn a nested dictionary, like {"name": 1}}` vs {"my.name": 1}

Definition at line 733 of file ros2.py.

◆ get_rostime()

rosros.ros2.get_rostime ( )

Returns current ROS2 time, as `rclpy.time.Time`.

Definition at line 1137 of file ros2.py.

◆ get_service_definition()

rosros.ros2.get_service_definition (   srv_or_type)

Returns ROS2 service type definition text.

Parameters
srv_or_typecanonical or full class name like "std_srvs/SetBool" or "std_srvs/srv/SetBool", or class instance like `std_srvs.srv.SetBool()`, or class object like `std_srvs.srv.SetBool`
Returns
ROS2 service type definition text

Definition at line 1490 of file ros2.py.

◆ get_service_request_class()

rosros.ros2.get_service_request_class (   srv_or_type)

Returns ROS2 service request class object.

Parameters
srv_or_typecanonical or full class name like "std_srvs/SetBool" or "std_srvs/srv/SetBool", or class instance like `std_srvs.srv.SetBool()`, or class object like `std_srvs.srv.SetBool`
Returns
ROS2 service request class object, like `std_srvs.srv.SetBool.Request`

Definition at line 1503 of file ros2.py.

◆ get_service_response_class()

rosros.ros2.get_service_response_class (   srv_or_type)

Returns ROS2 service response class object.

Parameters
srv_or_typecanonical or full class name like "std_srvs/SetBool" or "std_srvs/srv/SetBool", or class instance like `std_srvs.srv.SetBool()`, or class object like `std_srvs.srv.SetBool`
Returns
ROS2 service response class object, like `std_srvs.srv.SetBool.Response`

Definition at line 1515 of file ros2.py.

◆ get_services()

rosros.ros2.get_services (   node = None,
  namespace = None,
  include_types = True 
)

Returns all available ROS2 services, as `[(service name, [type name, ]), ]`.

Parameters
nodefull name of the node to return services for, if any
namespacefull or partial namespace to scope services from
include_typesif false, type names will be returned as an empty list

Definition at line 1115 of file ros2.py.

◆ get_topic_qos()

rosros.ros2.get_topic_qos (   topic,
  cls_or_typename,
  queue_size = 10,
  publish = False 
)

Returns dictionary for populating rclpy.qos.QoSProfile compatible with counterparts on topic.

Parameters
topictopic full name
cls_or_typenamemessage type class or name
queue_sizepopulates "depth"
publishwhether to return QoS settings for creating a publisher, by default returns settings for a subscription
Returns
{"depth", "reliability", "durability"}

Definition at line 1093 of file ros2.py.

◆ get_topics()

rosros.ros2.get_topics ( )

Returns all available ROS2 topics, as `[(topic name, [type name, ]), ]`.

Definition at line 1078 of file ros2.py.

◆ has_param()

rosros.ros2.has_param (   name)

Returns whether the parameter exists.

Parameters
namefull name of the parameter in node namespace

Definition at line 699 of file ros2.py.

◆ init_node()

rosros.ros2.init_node (   name,
  args = None,
  namespace = None,
  anonymous = False,
  log_level = None,
  enable_rosout = True,
  multithreaded = True,
  reentrant = False 
)

Initializes rclpy and creates ROS2 node.

Parameters
namenode name, without namespace
argslist of command-line arguments for the node
namespacenode namespace override
anonymouswhether to auto-generate a unique name for the node, using the given name as base
log_levellevel to set for ROS logging (name like "DEBUG" or one of `logging` constants like `logging.DEBUG`)
enable_rosout`False` to suppress auto-publication of rosout
multithreadeduse `MultiThreadedExecutor` instead of `SingleThreadedExecutor`
reentrantuse `ReentrantCallbackGroup` instead of `MutuallyExclusiveCallbackGroup`
Returns
`rclpy.node.Node`

Definition at line 612 of file ros2.py.

◆ init_params()

rosros.ros2.init_params (   defaults = None,
**  defaultkws 
)

Declares all parameters on node from defaults dictionary.

Parameters
defaultsnested dictionary with suitable keys and values for ROS (keys must be valid namespace names, list values must not contain nested values)
defaultkwsparameters as key=value
Returns
full nested parameters dictionary, combined from given defaults and externally set parameters on the node

Definition at line 674 of file ros2.py.

◆ is_ros_message()

rosros.ros2.is_ros_message (   val)

Returns whether value is a ROS2 message or service request/response class or instance.

Parameters
vallike `std_msgs.msg.Bool()` or `std_srvs.srv.SetBoolRequest`
Returns
True if value is a ROS2 message or service request/response class or instance, False otherwise

Definition at line 1525 of file ros2.py.

◆ is_ros_service()

rosros.ros2.is_ros_service (   val)

Returns whether value is a ROS2 service class object.

Definition at line 1530 of file ros2.py.

◆ is_ros_time()

rosros.ros2.is_ros_time (   val)

Returns whether value is a ROS2 time/duration class or instance.

Definition at line 1535 of file ros2.py.

◆ make_duration()

rosros.ros2.make_duration (   secs = 0,
  nsecs = 0 
)

Returns an rclpy.duration.Duration.

Definition at line 1541 of file ros2.py.

◆ make_time()

rosros.ros2.make_time (   secs = 0,
  nsecs = 0 
)

Returns a ROS2 time, as rclpy.time.Time.

Definition at line 1546 of file ros2.py.

◆ ok()

rosros.ros2.ok ( )

Returns whether ROS2 has been initialized and is not shut down.

Definition at line 774 of file ros2.py.

◆ on_shutdown()

rosros.ros2.on_shutdown (   callback,
args,
**  kwargs 
)

Registers function to be called on shutdown, after node has been torn down.

Function is called with given arguments.

Definition at line 784 of file ros2.py.

◆ register_init()

rosros.ros2.register_init (   node)

Informs `rosros` of ROS2 having been initialized outside of `init_node()`.

Parameters
node`rclpy.node.Node` instance to use for ROS operations

Definition at line 654 of file ros2.py.

◆ remap_name()

rosros.ros2.remap_name (   name,
  namespace = None 
)

Returns the absolute remapped topic/service name if mapping exists.

Parameters
namename to seek exact remapping for
namespacenamespace to resolve relative and private names to, by default current node namespace
Returns
remapped resolved name, or original if not mapped

Definition at line 1150 of file ros2.py.

◆ resolve_name()

rosros.ros2.resolve_name (   name,
  namespace = None 
)

Returns absolute remapped name, namespaced under current node if relative or private.

Parameters
namespacenamespace to use if not current node full name

Definition at line 1163 of file ros2.py.

◆ scalar()

rosros.ros2.scalar (   typename)

Returns unbounded scalar type from ROS2 message data type.

Like "uint8" from "uint8[]", or "string" from "string<=10[<=5]". Returns type unchanged if not a collection or bounded type.

Definition at line 1568 of file ros2.py.

◆ serialize_message()

rosros.ros2.serialize_message (   msg)

Returns ROS2 message or service request/response as a serialized binary of `bytes()`.

Definition at line 1551 of file ros2.py.

◆ set_param()

rosros.ros2.set_param (   name,
  value,
  descriptor = None 
)

Sets a parameter on the node, auto-declaring it if unknown so far.

Parameters
nameparameter full name
valueparameter value to set
descriptoroptional `rcl_interfaces.msg.ParameterDescriptor`
Returns
the set value

Definition at line 749 of file ros2.py.

◆ shutdown()

rosros.ros2.shutdown (   reason = None)

Shuts down ROS2 execution, if any.

Parameters
reasonshutdown reason to log, if any

Definition at line 887 of file ros2.py.

◆ sleep()

rosros.ros2.sleep (   duration)

Sleeps for the specified duration in ROS time.

Raises error on ROS shutdown or ROS time jumping backwards

Parameters
durationtime to sleep, as seconds or ROS duration, <=0 returns immediately

Definition at line 1199 of file ros2.py.

◆ spin()

rosros.ros2.spin ( )

Spins ROS2 node forever.

Definition at line 819 of file ros2.py.

◆ spin_once()

rosros.ros2.spin_once (   timeout = None)

Executes one pending ROS2 operation or waits until timeout.

Waits forever if timeout not given or negative.

Parameters
timeouttime to wait at most, as seconds or ROS2 duration; None or <0 waits forever

Definition at line 842 of file ros2.py.

◆ spin_until_future_complete()

rosros.ros2.spin_until_future_complete (   future,
  timeout = None 
)

Spins ROS2 until future complete or timeout reached or ROS shut down.

Parameters
futureobject with `concurrent.futures.Future`-conforming interface to complete
timeouttime to wait, as seconds or ROS2 duration

Definition at line 863 of file ros2.py.

◆ start_spin()

rosros.ros2.start_spin ( )

Sets ROS2 node spinning forever in a background thread.

Definition at line 803 of file ros2.py.

◆ time_message()

rosros.ros2.time_message (   val,
  to_message = True,
  clock_type = None 
)

Converts ROS2 time/duration between `rclpy` and `builtin_interfaces` objects.

Parameters
valROS2 time/duration object from `rclpy` or `builtin_interfaces`
to_messagewhether to convert from `rclpy` to `builtin_interfaces` or vice versa
clock_typeClockType for converting to `rclpy.Time`, defaults to `ROS_TIME`
Returns
value converted to appropriate type, or original value if not convertible

Definition at line 1581 of file ros2.py.

◆ to_duration()

rosros.ros2.to_duration (   val)

Returns value as ROS2 duration if convertible (int/float/time/datetime/decimal), else value.

Convertible int/float/time/datetime/decimal/builtin_interfaces.Time.

Definition at line 1597 of file ros2.py.

◆ to_nsec()

rosros.ros2.to_nsec (   val)

Returns value in nanoseconds if value is ROS2 time/duration, else value.

Definition at line 1612 of file ros2.py.

◆ to_sec()

rosros.ros2.to_sec (   val)

Returns value in seconds if value is ROS2 time/duration, else value.

Definition at line 1621 of file ros2.py.

◆ to_sec_nsec()

rosros.ros2.to_sec_nsec (   val)

Returns value as (seconds, nanoseconds) if value is ROS2 time/duration, else value.

Definition at line 1631 of file ros2.py.

◆ to_time()

rosros.ros2.to_time (   val)

Returns value as ROS2 time if convertible, else value.

Convertible int/float/duration/datetime/decimal/builtin_interfaces.Time.

Definition at line 1647 of file ros2.py.

◆ wait_for_publisher()

rosros.ros2.wait_for_publisher (   topic,
  timeout = None,
  cls_or_typename = None 
)

Blocks until topic has at least one publisher.

Parameters
topicname of topic to open
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever
cls_or_typenamemessage type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
Returns
whether a publisher is available

Definition at line 1215 of file ros2.py.

◆ wait_for_service()

rosros.ros2.wait_for_service (   service,
  timeout = None,
  cls_or_typename = None 
)

Blocks until service is available.

Parameters
servicename of service
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever
cls_or_typenameservice type to expect if any, as ROS service class object like `std_msgs.msg.Bool` or service type name like "std_srvs/SetBool"
Returns
whether the service is available

Definition at line 1267 of file ros2.py.

◆ wait_for_subscriber()

rosros.ros2.wait_for_subscriber (   topic,
  timeout = None,
  cls_or_typename = None 
)

Blocks until topic has at least one subscriber.

Parameters
topicname of topic to open
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever
cls_or_typenamemessage type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
Returns
whether a subscriber is available

Definition at line 1241 of file ros2.py.

Variable Documentation

◆ AnyMsg

rosros.ros2.AnyMsg = patch.AnyMsg

Stand-in for `rospy.AnyMsg` with equivalent interface.

Definition at line 57 of file ros2.py.

◆ args

rosros.ros2.args

Definition at line 787 of file ros2.py.

◆ CALLBACK_GROUP

rosros.ros2.CALLBACK_GROUP = None

`rclpy.callback_groups.CallbackGroup` instance

Definition at line 100 of file ros2.py.

◆ called

rosros.ros2.called

Definition at line 788 of file ros2.py.

◆ DDS_TYPES

dict rosros.ros2.DDS_TYPES
Initial value:
1= {"boolean": "bool",
2 "float": "float32",
3 "double": "float64",
4 "octet": "byte",
5 "short": "int16",
6 "unsigned short": "uint16",
7 "long": "int32",
8 "unsigned long": "uint32",
9 "long long": "int64",
10 "unsigned long long": "uint64", }

Data Distribution Service types to ROS builtins.

Definition at line 76 of file ros2.py.

◆ EXECUTOR

rosros.ros2.EXECUTOR = None

`rclpy.executors.Executor` instance

Definition at line 103 of file ros2.py.

◆ FAMILY

str rosros.ros2.FAMILY = "rclpy"

ROS Python module family, "rclpy".

Definition at line 94 of file ros2.py.

◆ func

rosros.ros2.func

Definition at line 787 of file ros2.py.

◆ kwargs

rosros.ros2.kwargs

Definition at line 787 of file ros2.py.

◆ NODE

rosros.ros2.NODE = None

`rclpy.node.Node` instance

Definition at line 97 of file ros2.py.

◆ PARAM_SEPARATOR

str rosros.ros2.PARAM_SEPARATOR = "."

Separator char between ROS2 parameter namespace parts.

Definition at line 88 of file ros2.py.

◆ PRIVATE_PREFIX

str rosros.ros2.PRIVATE_PREFIX = "~"

Prefix for "private" names, auto-namespaced under current namespace.

Definition at line 91 of file ros2.py.

◆ ROS_ALIAS_TYPES

dict rosros.ros2.ROS_ALIAS_TYPES = {"byte": "uint8", "char": "int8"}

Mapping between ROS type aliases and real types, like {"byte": "uint8"}.

Definition at line 73 of file ros2.py.

◆ ROS_TIME_CLASSES

dict rosros.ros2.ROS_TIME_CLASSES
Initial value:
1= {rclpy.time.Time: "builtin_interfaces/Time",
2 builtin_interfaces.msg.Time: "builtin_interfaces/Time",
3 rclpy.duration.Duration: "builtin_interfaces/Duration",
4 builtin_interfaces.msg.Duration: "builtin_interfaces/Duration"}

ROS2 time/duration types and message types mapped to type names.

Definition at line 63 of file ros2.py.

◆ ROS_TIME_MESSAGES

dict rosros.ros2.ROS_TIME_MESSAGES
Initial value:
1= {rclpy.time.Time: builtin_interfaces.msg.Time,
2 rclpy.duration.Duration: builtin_interfaces.msg.Duration}

ROS2 time/duration types mapped to message types.

Definition at line 69 of file ros2.py.

◆ ROS_TIME_TYPES

list rosros.ros2.ROS_TIME_TYPES = ["builtin_interfaces/Time", "builtin_interfaces/Duration"]

ROS2 time/duration message types.

Definition at line 60 of file ros2.py.

◆ SHUTDOWN

bool rosros.ros2.SHUTDOWN = False

Flag for `shutdown()` been called.

Definition at line 109 of file ros2.py.

◆ SHUTDOWN_CALLBACKS

list rosros.ros2.SHUTDOWN_CALLBACKS = []

Callbacks registered with on_shutdown()

Definition at line 112 of file ros2.py.

◆ SPINNER

rosros.ros2.SPINNER = None

`threading.Thread` running `EXECUTOR.spin()`

Definition at line 106 of file ros2.py.