Simple unified interface to ROS1 / ROS2 Python API
Index
Installation
Example usage
ROS core functionality
Patches in ROS1
Patches in ROS2
ROS API helpers
Converting an existing package
API documentation
View the Project on GitHub suurjaak/rosros
Functionality for creating and operating a ROS node.
Objects returned are standard rospy
/ rclpy
API objects, patched with
additional members for a unified interface conforming to ROS1 API.
Name | Description | Arguments |
---|---|---|
Startup, spin and shutdown | ||
rosros.init_node | initializes ROS and creates ROS node (and returns Node object in ROS2) | name, args=None, namespace=None, anonymous=True, log_level=None, enable_rosout=True, multithreaded=True, reentrant=False |
rosros.start_spin | sets ROS node spinning forever in a background thread | |
rosros.spin | spins ROS node forever | |
rosros.spin_once | waits until timeout in ROS1; executes one ROS operation or waits until timeout in ROS2 | timeout=None |
rosros.spin_until_future_complete | spins ROS until future complete or timeout reached or ROS shut down | future, timeout=None |
rosros.ok | returns whether ROS has been initialized and is not shut down | |
rosros.on_shutdown | registers function to be called on shutdown | callback, *args, **kwargs |
rosros.shutdown | shuts down live ROS node, if any | reason=None |
Parameters | ||
rosros.init_params | sets all parameters on node from defaults dictionary, returns full parameters dictionary. | defaults=None, **defaultkws |
In ROS2, auto-declares unregistered parameters. | ||
rosros.has_param | returns whether the parameter exists | name |
rosros.get_param | returns parameter value from current ROS node | name, default=None, autoset=True |
rosros.get_param_names | returns the names of all current ROS node parameters | |
rosros.get_params | returns the current ROS node parameters, by default as nested dictionary | nested=True |
rosros.set_param | sets a parameter on the node. | name, value, descriptor=None |
In ROS2, parameter will be auto-declared if unknown so far. | ||
rosros.delete_param | deletes parameter from the node | name |
Topics, services, timers and rates | ||
rosros.create_publisher | returns a ROS publisher instance | topic, cls_or_typename, latch=False, queue_size=0, **qosargs |
rosros.create_subscriber | returns a ROS subscriber instance | topic, cls_or_typename, callback, callback_args=None, queue_size=0, raw=False, **qosargs |
rosros.create_service | returns a ROS service server instance, for providing a service | service, cls_or_typename, callback, **qosargs |
rosros.create_client | returns a ROS service client instance, for invoking a service | service, cls_or_typename, **qosargs |
rosros.create_timer | returns a ROS timer instance | period, callback, oneshot=False, immediate=False |
rosros.create_rate | returns a ROS rate instance, for sleeping at a fixed rate | frequency |
rosros.destroy_entity | closes the given publisher, subscriber, service client, service server, or timer instance | item |
rosros.AnyMsg | rospy.AnyMsg in ROS1, stand-in class with equivalent functionality in ROS2 | |
sleep | sleeps for the specified duration in ROS time | duration |
wait_for_publisher | blocks until topic has at least one publisher | topic, timeout=None, cls_or_typename=None |
wait_for_subscriber | blocks until topic has at least one subscriber | topic, timeout=None, cls_or_typename=None |
wait_for_service | blocks until service is available | service, timeout=None, cls_or_typename=None |
ROS bags | ||
rosros.Bag | ROS bag reader and writer; | |
rosbag.Bag in ROS1 with some additional functionality; | ||
equivalent class in ROS2, using the ROS2 default SQLite format | ||
Information queries | ||
rosros.get_namespace | returns ROS node namespace | |
rosros.get_node_name | returns ROS node full name with namespace | |
rosros.get_nodes | returns all ROS nodes, as [node full name, ] | |
rosros.get_topics | returns all available ROS topics, as [(topic name, [type name, ]), ] | |
rosros.get_services | returns all available ROS services, as [(service name, [type name, ]), ] | |
rosros.remap_name | returns the absolute remapped topic/service name if mapping exists | name, namespace=None |
rosros.resolve_name | returns absolute remapped name, namespaced under current node if relative or private | name, namespace=None |
Miscellaneous | ||
rosros.get_logger | returns logging.Logger for logging to ROS log handler; | |
logger supports additional keywords __once__, __throttle__, __throttle_identical__ | ||
rosros.get_ros_version | returns ROS version information as a data dictionary | |
rosros.get_rostime | returns ROS time instance for current ROS clock time | |
rosros.register_init | informs rosros of ROS having been initialized outside of init_node() . | node=None |
Giving node as argument is mandatory in ROS2. |
Additional functionality patched onto rospy
classes for convenience:
rospy.ServiceProxy.call_async(*args, **kwargs)
:
asyncio.Future
-like response
rospy.ServiceProxy.wait_for_service(timeout=None, timeout_sec=None)
:
waits for service to become available, returns True
, or False
on timeout
rospy.ServiceProxy.service_is_ready()
:
rospy.Subscriber
:
raw=True
rosbag.Bag.get_message_definition(msg_or_type)
:
rosbag.Bag.get_message_class(typename, typehash=None)
:
rosbag.Bag.get_message_type_hash(msg_or_type)
:
rosbag.Bag.get_topic_info()
:
{(topic, typename, typehash): count}
rosbag.Bag.reindex_file(f)
:
The following classes are patched with full conformity to their equivalents in ROS:
rclpy.client.Client
rclpy.publisher.Publisher
cclpy.service.Service
rclpy.subscription.Subscription
rclpy.duration.Duration
rclpy.time.Time
rclpy.timer.Rate
rclpy.timer.Timer
E.g. durations support +-*/
arithmetic,
and publisher / subscriber provide .md5sum
for message type hash.