迁移 Python 包参考

本页是关于如何将 Python 包从 ROS 1 迁移到 ROS 2 的参考。 如果这是您第一次迁移 Python 包,请先按照 本指南迁移示例 Python 包 进行操作。

构建工具

ROS 2 不使用 catkin_makecatkin_make_isolatedcatkin build,而是使用命令行工具 colcon 来构建和安装一组软件包。

请参阅 初学者教程 以开始使用 colcon

构建系统

对于纯 Python 软件包,ROS 2 使用 Python 开发人员熟悉的标准 setup.py 安装机制。

更新文件以使用 setup.py

如果 ROS 1 包仅使用 CMake 调用 setup.py 文件,并且不包含除 Python 代码之外的任何内容(例如没有消息、服务等),则应将其转换为 ROS 2 中的纯 Python 包:

  • 在“package.xml”文件中更新或添加构建类型:

    <export>
      <build_type>ament_python</build_type>
    </export>
    
  • 删除“CMakeLists.txt”文件

  • 将“setup.py”文件更新为标准 Python 安装脚本

ROS 2 仅支持 Python 3。 虽然每个软件包都可以选择同时支持 Python 2,但如果它使用其他 ROS 2 软件包提供的任何 API,则必须使用 Python 3 调用可执行文件。

更新源代码

节点初始化

在 ROS 1 中:

rospy.init_node('asdf')

rospy.loginfo('Created node')

在 ROS 2 中:

rclpy.init(args=sys.argv)
node = rclpy.create_node('asdf')

node.get_logger().info('Created node')

ROS 参数

在 ROS 1 中:

 port = rospy.get_param('port', '/dev/ttyUSB0')
 assert isinstance(port, str), 'port parameter must be a str'

 baudrate = rospy.get_param('baudrate', 115200)
 assert isinstance(baudrate, int), 'baudrate parameter must be an integer'

rospy.logwarn('port: ' + port)

在 ROS 2 中:

port = node.declare_parameter('port', '/dev/ttyUSB0').value
assert isinstance(port, str), 'port parameter must be a str'

baudrate = node.declare_parameter('baudrate', 115200).value
assert isinstance(baudrate, int), 'baudrate parameter must be an integer'

node.get_logger().warn('port: ' + port)

创建发布者

在 ROS 1 中:

pub = rospy.Publisher('chatter', String)
# or
pub = rospy.Publisher('chatter', String, queue_size=10)

In ROS 2:

pub = node.create_publisher(String, 'chatter', rclpy.qos.QoSProfile())
# or
pub = node.create_publisher(String, 'chatter', 10)

Creating a Subscriber

在 ROS 1 中:

sub = rospy.Subscriber('chatter', String, callback)
# or
sub = rospy.Subscriber('chatter', String, callback, queue_size=10)

在 ROS 2 中:

sub = node.create_subscription(String, 'chatter', callback, rclpy.qos.QoSProfile())
# or
sub = node.create_subscription(String, 'chatter', callback, 10)

创建一个服务

在 ROS 1 中:

srv = rospy.Service('add_two_ints', AddTwoInts, add_two_ints_callback)

在 ROS 2 中:

srv = node.create_service(AddTwoInts, 'add_two_ints', add_two_ints_callback)

Creating a Service Client

在 ROS 1 中:

rospy.wait_for_service('add_two_ints')
add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
resp = add_two_ints(req)

在 ROS 2 中:

add_two_ints = node.create_client(AddTwoInts, 'add_two_ints')
while not add_two_ints.wait_for_service(timeout_sec=1.0):
    node.get_logger().info('service not available, waiting again...')
resp = add_two_ints.call_async(req)
rclpy.spin_until_future_complete(node, resp)