|
rosros 0.2.5
Simple unified interface to ROS1 / ROS2 Python API
|
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()` | |
ROS2 core interface.
|
protected |
|
protected |
|
protected |
| rosros.ros2.canonical | ( | typename | ) |
| rosros.ros2.create_client | ( | service, | |
| cls_or_typename, | |||
| ** | qosargs | ||
| ) |
Returns a ROS2 service client instance, for invoking a service.
| service | name of service to invoke |
| cls_or_typename | ROS2 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool" |
| qosargs | additional key-value arguments for ROS2 `QoSProfile`, like `reliability` |
| rosros.ros2.create_publisher | ( | topic, | |
| cls_or_typename, | |||
latch = False, |
|||
queue_size = 0, |
|||
| ** | qosargs | ||
| ) |
Returns a ROS2 publisher instance.
| topic | name of topic to open |
| cls_or_typename | ROS2 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
| latch | provide last published message to new subscribers (sets `DurabilityPolicy.TRANSIENT_LOCAL`) |
| queue_size | queue size of outgoing messages (0 or None: infinite) |
| qosargs | additional key-value arguments for ROS2 `QoSProfile`, like `reliability` |
| rosros.ros2.create_rate | ( | frequency | ) |
| rosros.ros2.create_service | ( | service, | |
| cls_or_typename, | |||
| callback, | |||
| ** | qosargs | ||
| ) |
Returns a ROS2 service server instance, for providing a service.
| service | name of service to provide |
| cls_or_typename | ROS2 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool" |
| callback | callback 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)`. |
| qosargs | additional key-value arguments for ROS2 `QoSProfile`, like `reliability` |
| rosros.ros2.create_subscriber | ( | topic, | |
| cls_or_typename, | |||
| callback, | |||
callback_args = None, |
|||
queue_size = 0, |
|||
raw = False, |
|||
| ** | qosargs | ||
| ) |
Returns a ROS2 subscriber instance.
| topic | name of topic to listen to |
| cls_or_typename | ROS2 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
| callback | callback function, invoked with received message, and with additional arguments if given |
| callback_args | additional arguments to pass to the callback, if any, invoked as `callback(msg, callback_args)´ |
| queue_size | queue size of incoming messages (0 or None: infinite) |
| raw | invoke callback with serialized message bytes |
| qosargs | additional key-value arguments for ROS2 `QoSProfile`, like `reliability`. `__autodetect` will look up current publishers on the topic and create a compatible QoS. |
| rosros.ros2.create_timer | ( | period, | |
| callback, | |||
oneshot = False, |
|||
immediate = False |
|||
| ) |
Returns a ROS2 timer instance.
| period | desired period between callbacks, as seconds or ROS duration |
| callback | callback function invoked on timer, with no arguments |
| oneshot | whether to fire only once |
| immediate | whether to fire once immediately instead of waiting one period |
| rosros.ros2.delete_param | ( | name | ) |
| rosros.ros2.deserialize_message | ( | raw, | |
| cls_or_typename | |||
| ) |
| rosros.ros2.destroy_entity | ( | item | ) |
| rosros.ros2.format_param_name | ( | name | ) |
| 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:
| rosros.ros2.get_message_class | ( | msg_or_type | ) |
Returns ROS2 message / service class object.
| msg_or_type | full or canonical class name, like "std_msgs/Bool" or "std_srvs/SetBool" or "std_srvs/SetBoolRequest"; or class instance like `std_msgs.msg.Bool()` |
| 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.
| msg_or_type | canonical 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` |
| full | include definitions of nested types, separated by "\n---\nMSG: pkg/Type\n" (ignored for service request/response types) |
| rosros.ros2.get_message_fields | ( | val | ) |
| rosros.ros2.get_message_header | ( | val | ) |
| rosros.ros2.get_message_type | ( | msg_or_cls | ) |
Returns ROS2 message / service canonical type name, like "std_msgs/Header".
Returns "*" for `AnyMsg`.
| msg_or_cls | class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool` |
| rosros.ros2.get_message_type_hash | ( | msg_or_type | ) |
| rosros.ros2.get_message_value | ( | msg, | |
| name, | |||
default = ... |
|||
| ) |
| rosros.ros2.get_node_name | ( | ) |
| rosros.ros2.get_nodes | ( | ) |
| rosros.ros2.get_package_share_directory | ( | name | ) |
| rosros.ros2.get_param | ( | name, | |
default = None, |
|||
autoset = True |
|||
| ) |
Returns parameter value from current ROS2 node.
| default | optional default to return if parameter unknown |
| autoset | set default value to node parameter if unknown |
| KeyError | if parameter not set and default not given |
| rosros.ros2.get_param_names | ( | ) |
| rosros.ros2.get_params | ( | nested = True | ) |
| rosros.ros2.get_rostime | ( | ) |
| rosros.ros2.get_service_definition | ( | srv_or_type | ) |
Returns ROS2 service type definition text.
| srv_or_type | canonical 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` |
| rosros.ros2.get_service_request_class | ( | srv_or_type | ) |
Returns ROS2 service request class object.
| srv_or_type | canonical 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` |
| rosros.ros2.get_service_response_class | ( | srv_or_type | ) |
Returns ROS2 service response class object.
| srv_or_type | canonical 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` |
| rosros.ros2.get_services | ( | node = None, |
|
namespace = None, |
|||
include_types = True |
|||
| ) |
Returns all available ROS2 services, as `[(service name, [type name, ]), ]`.
| node | full name of the node to return services for, if any |
| namespace | full or partial namespace to scope services from |
| include_types | if false, type names will be returned as an empty list |
| 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.
| topic | topic full name |
| cls_or_typename | message type class or name |
| queue_size | populates "depth" |
| publish | whether to return QoS settings for creating a publisher, by default returns settings for a subscription |
| rosros.ros2.get_topics | ( | ) |
| rosros.ros2.has_param | ( | name | ) |
| 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.
| name | node name, without namespace |
| args | list of command-line arguments for the node |
| namespace | node namespace override |
| anonymous | whether to auto-generate a unique name for the node, using the given name as base |
| log_level | level 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 |
| multithreaded | use `MultiThreadedExecutor` instead of `SingleThreadedExecutor` |
| reentrant | use `ReentrantCallbackGroup` instead of `MutuallyExclusiveCallbackGroup` |
| rosros.ros2.init_params | ( | defaults = None, |
|
| ** | defaultkws | ||
| ) |
Declares all parameters on node from defaults dictionary.
| defaults | nested dictionary with suitable keys and values for ROS (keys must be valid namespace names, list values must not contain nested values) |
| defaultkws | parameters as key=value |
| rosros.ros2.is_ros_message | ( | val | ) |
Returns whether value is a ROS2 message or service request/response class or instance.
| val | like `std_msgs.msg.Bool()` or `std_srvs.srv.SetBoolRequest` |
| rosros.ros2.is_ros_service | ( | val | ) |
| rosros.ros2.is_ros_time | ( | val | ) |
| rosros.ros2.make_duration | ( | secs = 0, |
|
nsecs = 0 |
|||
| ) |
| rosros.ros2.make_time | ( | secs = 0, |
|
nsecs = 0 |
|||
| ) |
| rosros.ros2.ok | ( | ) |
| rosros.ros2.on_shutdown | ( | callback, | |
| * | args, | ||
| ** | kwargs | ||
| ) |
| rosros.ros2.register_init | ( | node | ) |
| rosros.ros2.remap_name | ( | name, | |
namespace = None |
|||
| ) |
Returns the absolute remapped topic/service name if mapping exists.
| name | name to seek exact remapping for |
| namespace | namespace to resolve relative and private names to, by default current node namespace |
| rosros.ros2.resolve_name | ( | name, | |
namespace = None |
|||
| ) |
| rosros.ros2.scalar | ( | typename | ) |
| rosros.ros2.serialize_message | ( | msg | ) |
| rosros.ros2.set_param | ( | name, | |
| value, | |||
descriptor = None |
|||
| ) |
| rosros.ros2.shutdown | ( | reason = None | ) |
| rosros.ros2.sleep | ( | duration | ) |
| rosros.ros2.spin_once | ( | timeout = None | ) |
| rosros.ros2.spin_until_future_complete | ( | future, | |
timeout = None |
|||
| ) |
| rosros.ros2.start_spin | ( | ) |
| rosros.ros2.time_message | ( | val, | |
to_message = True, |
|||
clock_type = None |
|||
| ) |
Converts ROS2 time/duration between `rclpy` and `builtin_interfaces` objects.
| val | ROS2 time/duration object from `rclpy` or `builtin_interfaces` |
| to_message | whether to convert from `rclpy` to `builtin_interfaces` or vice versa |
| clock_type | ClockType for converting to `rclpy.Time`, defaults to `ROS_TIME` |
| rosros.ros2.to_duration | ( | val | ) |
| rosros.ros2.to_nsec | ( | val | ) |
| rosros.ros2.to_sec | ( | val | ) |
| rosros.ros2.to_sec_nsec | ( | val | ) |
| rosros.ros2.to_time | ( | val | ) |
| rosros.ros2.wait_for_publisher | ( | topic, | |
timeout = None, |
|||
cls_or_typename = None |
|||
| ) |
Blocks until topic has at least one publisher.
| topic | name of topic to open |
| timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
| cls_or_typename | message type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
| rosros.ros2.wait_for_service | ( | service, | |
timeout = None, |
|||
cls_or_typename = None |
|||
| ) |
Blocks until service is available.
| service | name of service |
| timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
| cls_or_typename | service type to expect if any, as ROS service class object like `std_msgs.msg.Bool` or service type name like "std_srvs/SetBool" |
| rosros.ros2.wait_for_subscriber | ( | topic, | |
timeout = None, |
|||
cls_or_typename = None |
|||
| ) |
Blocks until topic has at least one subscriber.
| topic | name of topic to open |
| timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
| cls_or_typename | message type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
| rosros.ros2.AnyMsg = patch.AnyMsg |
| rosros.ros2.CALLBACK_GROUP = None |
| dict rosros.ros2.DDS_TYPES |
Data Distribution Service types to ROS builtins.
| rosros.ros2.EXECUTOR = None |
| str rosros.ros2.FAMILY = "rclpy" |
| str rosros.ros2.PARAM_SEPARATOR = "." |
| str rosros.ros2.PRIVATE_PREFIX = "~" |
| dict rosros.ros2.ROS_ALIAS_TYPES = {"byte": "uint8", "char": "int8"} |
| dict rosros.ros2.ROS_TIME_CLASSES |
ROS2 time/duration types and message types mapped to type names.
| dict rosros.ros2.ROS_TIME_MESSAGES |
| list rosros.ros2.ROS_TIME_TYPES = ["builtin_interfaces/Time", "builtin_interfaces/Duration"] |
| bool rosros.ros2.SHUTDOWN = False |
| list rosros.ros2.SHUTDOWN_CALLBACKS = [] |