Simple unified interface to ROS1 / ROS2 Python API
Index
Installation
Example usage
ROS core functionality
ROS API helpers
Converting an existing package
Existing ROS1 package to ROS1/ROS2
Existing ROS2 package to ROS1/ROS2
API documentation
View the Project on GitHub suurjaak/rosros
rosros can be used as a (mostly) drop-in replacement for rospy
to make a ROS1 package equally usable under ROS2 - if the code relies only
on rospy, and does not go too deeply into using ROS1 specifics like rosgraph.
rospy imports can be replaced with rosros.rospify, e.g.
import threading
from rosros import rospify as rospy
from std_msgs.msg import String
rospy.init_node("talker", anonymous=True)
pub = rospy.Publisher("chatter", String, queue_size=10)
rate = rospy.Rate(10) # 10hz
threading.Thread(target=rospy.spin).start() # Concession for ROS2: spin is always needed
while not rospy.is_shutdown():
hello_str = "hello world %s" % rospy.get_time()
rospy.loginfo(hello_str)
pub.publish(hello_str)
rate.sleep()
In ROS1 it provides rospy, and in ROS2 it provides matching API classes and functions.
Main behavioral differences of rospify in ROS2 vs ROS1:
Subscriber.get_num_connections() always returns 0, as ROS2 does not provide this informationAnyMsg needs the publisher existingon_shutdown() are called after node shutdown, not beforerosros.rospify.get_master() requires local node to be initialized, unlike rospy.get_master()rosros.rospify.SubscribeListener does nothing
rosros can also be used as a (mostly) drop-in replacement for rclpy
to make a ROS2 package equally usable under ROS1 - if the code mainly relies on
rclpy module and does not go deep into using ROS2 specifics like builtin_interfaces.
rclpy imports can be replaced with rosros.rclify, e.g.
from rosros import rclify as rclpy
from std_msgs.msg import String
class MinimalPublisher(rclpy.node.Node):
def __init__(self):
super().__init__("minimal_publisher")
self.publisher_ = self.create_publisher(String, "chatter", 10)
timer_period = 0.1 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
def timer_callback(self):
msg = String()
msg.data = "Hello World: %d" % self.i
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1
rclpy.init()
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
In ROS2, rclify provides rclpy, and in ROS1 it provides
matching API modules and classes and functions.
Covers all the parts of rclpy.node that are supportable in ROS1, focused on:
creating nodes, publishing and subscribing topics, providing and invoking services,
working with rates and timers.
Main behavioral differences of rclify in ROS1 vs ROS2:
depth (taken as queue_size),
durability equaling TRANSIENT_LOCAL (taken as latch=True)
Methods pertaining to unsupported functionality do nothing and return None.
Unsupported arguments in methods are ignored.