1. 使用 RCLPY 实现话题
  2. 创建工作空间和功能包
cd d2lros2/chapt3/
mkdir -p chapt2_ws/src
 
cd chapt3/chapt3_ws/src/
ros2 pkg create example_topic_rclpy  --build-type ament_python --dependencies rclpy
  1. 创建节点文件
cd example_topic_rclpy/example_topic_rclpy
touch topic_subscribe_02.py  # Linux 创建新文件
touch topic_publisher_02.py
  1. 编写发布者:Node.create_publisher
    • msg_type – 发布者将要发布的消息类型。
    • topic (str) – 发布者将要发布到的主题名称。
    • qos_profile (Union[QoSProfile, int]) – 应用于发布者的QoSProfile或历史深度。如果提供了历史深度,则QoS历史设置为RMW_QOS_POLICY_HISTORY_KEEP_LAST,QoS历史深度设置为参数的值,所有其他QoS设置设置为默认值。
    • callback_group (Optional[CallbackGroup]) – 发布者事件处理程序的回调组。如果为 None,则使用节点的默认回调组。
    • event_callbacks (Optional[PublisherEventCallbacks]) – 中间件事件的用户定义回调。
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
 
class NodePublisher02(Node):
    def __init__(self,name):
        super().__init__(name)
        self.get_logger().info("大家好,我是%s!" % name)
        self.command_publisher_ = self.create_publisher(String,"command", 10) 
        self.timer = self.create_timer(0.5, self.timer_callback)
    
    def timer_callback(self):
        """
        定时器回调函数
        """
        msg = String()
        msg.data = 'backup'
        self.command_publisher_.publish(msg) 
        self.get_logger().info(f'发布了指令:{msg.data}')    # 打印一下发布的数据
 
def main(args=None):
    rclpy.init(args=args) # 初始化rclpy
    node = NodePublisher02("topic_publisher_02")  # 新建一个节点
    rclpy.spin(node) # 保持节点运行,检测是否收到退出指令(Ctrl+C)
    rclpy.shutdown() # 关闭rclpy
  1. 编写订阅者:Node.create_subscription
    • msg_type – 订阅将订阅的 ROS 消息类型。
    • topic (str) – 订阅将订阅的主题名称。
    • callback (Callable[~MsgType], None]) – 当订阅收到消息时调用的用户定义回调函数。
    • qos_profile (Union[QoSProfile, int]) – 应用于订阅的QoSProfile或历史深度。如果提供了历史深度,则QoS历史设置为RMW_QOS_POLICY_HISTORY_KEEP_LAST,QoS历史深度设置为参数的值,所有其他QoS设置设置为默认值。
    • callback_group (Optional[CallbackGroup]) – 订阅的回调组。如果为 None,则使用节点的默认回调组。
    • event_callbacks (Optional[SubscriptionEventCallbacks]) – 中间件事件的用户定义回调。
    • raw (bool) – 如果为True,则接收到的消息将以原始二进制表示形式存储。
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
 
class NodeSubscribe02(Node):
    def __init__(self,name):
        super().__init__(name)
        self.get_logger().info("大家好,我是%s!" % name)
        # 创建订阅者
        self.command_subscribe_ = 
	        self.create_subscription(String,"command",self.command_callback,10)
 
    def command_callback(self,msg):
        speed = 0.0
        if msg.data == "backup":
            speed = -0.2
        self.get_logger().info(f'收到[{msg.data}]命令,发送速度{speed}')
 
def main(args=None):
    rclpy.init(args=args) # 初始化rclpy
    node = NodeSubscribe02("topic_subscribe_02")  # 新建一个节点
    rclpy.spin(node) # 保持节点运行,检测是否收到退出指令(Ctrl+C)
    rclpy.shutdown() # 关闭rclpy
  1. 修改 setup.py
    entry_points={
        'console_scripts': [
            "topic_publisher_02 = example_topic_rclpy.topic_publisher_02:main",
            "topic_subscribe_02 = example_topic_rclpy.topic_subscribe_02:main"
        ],
    },
  1. 运行:build + source + run
colcon build --packages-select example_topic_rclpy
 
source install/setup.bash
ros2 run example_topic_rclpy topic_publisher_02
 
cd chapt3/chapt3_ws/
source install/setup.bash
ros2 run example_topic_rclpy topic_subscribe_02
  1. 测试:使用 rqt 查看 Node Graph