ROS2动作

10 阅读7分钟

1. ROS2动作是什么

动作通信是ROS2中用于长时间运行、可反馈、可取消的任务的通信机制,适用于需要跟踪进度或中途干预的场景。 动作通信基于客户端-服务器模型,包含三个关键部分:

  • 目标(Goal):客户端发送的任务请求
  • 反馈(Feedback):服务器在执行过程中周期性返回的进度信息
  • 结果(Result):任务完成后服务器返回的最终状态

可以拿点外卖的过程来类比,下单点外卖就是发送任务请求的过程;app上显示外卖的实时信息就是不断反馈的过程;收到订单送达的通知就是表示任务完成(过程中随时可以取消外卖,或者更改外卖相关信息)

2. 动作通信模型

1.png 特点:

  • 客户端/服务端模型:在动作通信的过程中,客户端发送动作的目标——发布请求让机器人执行某动作;服务端 执行该动作——控制机器人完成动作,同时周期性反馈动作执行过程中的状态。动作执行完毕后,服务端再反馈一个动作结束的信息,整个通信过程结束。
  • 一对多通信:和服务一样,动作通信中的客户端可以有多个,大家都可以发送动作命令,但是服务端只 能有一个
  • 异步通信:因为存在反馈动作,那么动作是一种异步通信机制
  • 由服务+话题组成:动作的三个通信模块,有两个是服务, 一个是话题。ROS 2的动作API进行了高度封装,把这三个底层的通信通道(Goal、Result、Feedback)打包成了一个高级的 ActionClientActionServer 类。所以在代码层面,只需要写一个动作服务端节点一个动作客户端节点

3.动作通信编程示例

2.1创建接口功能包

创建接口功能包

ros2 pkg create --build-type ament_cmake learn_action_interface --license Apache-2.0

2.2创建服务接口

在learn_action_interface目录下创建action目录 接着在action目录下创建OrderFood.action:

# 请求:用户下单
string food_name
int32 quantity
---
# 结果:订单完成状态
bool success
string message
float32 total_time  # 总耗时(分钟)
---
# 反馈:过程状态更新
string status
int32 progress_percent
string current_step  # 下单中、商家已接单、骑手已取餐、配送中

2.3修改CMakeLists.txt和package.xml

在CMakeLists.txt添加内容:

find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
  "action/OrderFood.action"
)

在package.xml添加内容:

  <build_depend>rosidl_default_generators</build_depend>
  <exec_depend>rosidl_default_runtime</exec_depend>
  <member_of_group>rosidl_interface_packages</member_of_group>

2.4创建动作功能包

创建动作功能包

ros2 pkg create --build-type ament_python food_delivery --license Apache-2.0

2.5编写服务端节点(Python)

在food_delivery/food_delivery目录下创建order_server.py:

import random

import rclpy
from rclpy.action import ActionServer
from rclpy.node import Node
import time

from learn_action_interface.action import OrderFood


class OrderFoodServer(Node):
    def __init__(self):
        super().__init__('order_food_server')
        self._action_server = ActionServer(
            self,
            OrderFood,
            'order_food',
            self.execute_callback
        )
        self.get_logger().info('点外卖服务端已启动,等待用户下单...')
        
    def execute_callback(self, goal_handle):
        self.get_logger().info(f'收到新订单: {goal_handle.request.food_name} x{goal_handle.request.quantity}')
        
        # 初始化反馈和结果
        feedback_msg = OrderFood.Feedback()
        result = OrderFood.Result()
        
        # 步骤1: 商家确认订单 (0-20%)
        feedback_msg.status = "商家正在确认订单"
        feedback_msg.progress_percent = 10
        feedback_msg.current_step = "商家已接单"
        goal_handle.publish_feedback(feedback_msg)
        self.get_logger().info(f'反馈: {feedback_msg.status}')
        time.sleep(2)  # 模拟处理时间
        
        # 步骤2: 商家准备食物 (20-40%)
        feedback_msg.status = "商家正在准备食物"
        feedback_msg.progress_percent = 30
        feedback_msg.current_step = "食物准备中"
        goal_handle.publish_feedback(feedback_msg)
        self.get_logger().info(f'反馈: {feedback_msg.status}')
        time.sleep(2)
        
        # 步骤3: 骑手取餐 (40-60%)
        feedback_msg.status = "骑手正在取餐"
        feedback_msg.progress_percent = 50
        feedback_msg.current_step = "骑手已取餐"
        goal_handle.publish_feedback(feedback_msg)
        self.get_logger().info(f'反馈: {feedback_msg.status}')
        time.sleep(2)
        
        # 步骤4: 配送中 (60-90%)
        for progress in range(60, 91, 10):
            feedback_msg.status = f"配送中... {progress}%"
            feedback_msg.progress_percent = progress
            feedback_msg.current_step = "配送中"
            goal_handle.publish_feedback(feedback_msg)
            self.get_logger().info(f'反馈: {feedback_msg.status}')
            time.sleep(1.5)
        
        # 步骤5: 订单完成 (90-100%)
        feedback_msg.status = "订单即将送达"
        feedback_msg.progress_percent = 95
        feedback_msg.current_step = "即将送达"
        goal_handle.publish_feedback(feedback_msg)
        self.get_logger().info(f'反馈: {feedback_msg.status}')
        time.sleep(1)
        
        # 标记目标完成
        goal_handle.succeed()
        
        # 返回结果
        result.success = True
        result.message = f"{goal_handle.request.food_name} x{goal_handle.request.quantity} 已成功送达!"
        result.total_time = random.uniform(10, 30)
        
        self.get_logger().info(f'订单完成: {result.message}')
        return result


def main(args=None):
    rclpy.init(args=args)
    server = OrderFoodServer()
    rclpy.spin(server)
    server.destroy_node()
    rclpy.shutdown()

2.6编写客户端节点(Python)

在food_delivery/food_delivery目录下创建order_client.py:

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
import sys

from learn_action_interface.action import OrderFood


class OrderFoodClient(Node):
    def __init__(self):
        super().__init__('order_food_client')
        self._action_client = ActionClient(self, OrderFood, 'order_food')
        
    def send_order(self, food_name, quantity):
        goal_msg = OrderFood.Goal()
        goal_msg.food_name = food_name
        goal_msg.quantity = quantity
        
        self.get_logger().info(f'正在下单: {food_name} x{quantity}')
        
        # 等待服务端
        self._action_client.wait_for_server()
        self.get_logger().info('连接到外卖服务端...')
        
        # 发送目标
        self._send_goal_future = self._action_client.send_goal_async(
            goal_msg,
            feedback_callback=self.feedback_callback
        )
        
        # 等待目标被接受
        self._send_goal_future.add_done_callback(self.goal_response_callback)
        
    def goal_response_callback(self, future):
        goal_handle = future.result()
        if not goal_handle.accepted:
            self.get_logger().info('订单被拒绝')
            return
            
        self.get_logger().info('订单已被接受,开始配送...')
        
        # 获取结果
        self._get_result_future = goal_handle.get_result_async()
        self._get_result_future.add_done_callback(self.get_result_callback)
        
    def get_result_callback(self, future):
        result = future.result().result
        self.get_logger().info(f'订单结果: 成功={result.success}, 消息={result.message}, 总耗时={result.total_time:.1f}分钟')
        rclpy.shutdown()
        
    def feedback_callback(self, feedback_msg):
        feedback = feedback_msg.feedback
        self.get_logger().info(
            f'订单状态: {feedback.status} | '
            f'进度: {feedback.progress_percent}% | '
            f'步骤: {feedback.current_step}'
        )


def main(args=None):
    rclpy.init(args=args)
    
    # 从命令行参数获取食物和数量
    food_name = "披萨"
    quantity = 2
    if len(sys.argv) > 1:
        food_name = sys.argv[1]
    if len(sys.argv) > 2:
        quantity = int(sys.argv[2])
    
    client = OrderFoodClient()
    client.send_order(food_name, quantity)
    
    rclpy.spin(client)
    
    client.destroy_node()
    rclpy.shutdown()

2.7 修改setup.py和package.xml

修改setup.py文件:

entry_points={
        'console_scripts': [
            'order_client = food_delivery.order_client:main',
            'order_server = food_delivery.order_server:main',
        ],

在package.xml文件添加依赖:

<depend>learn_action_interface</depend>

2.8 构建并运行节点

colcon build
source install/setup.bash

ros2 run food_delivery order_server

#最后两个值为系统参数
ros2 run food_delivery order_client "麻辣烫" 3

2.9 输出示例

服务器端:

[INFO] [1775809823.337570440] [order_food_server]: 收到新订单: 麻辣烫 x3
[INFO] [1775809823.337930049] [order_food_server]: 反馈: 商家正在确认订单
[INFO] [1775809825.340235338] [order_food_server]: 反馈: 商家正在准备食物
[INFO] [1775809827.342656403] [order_food_server]: 反馈: 骑手正在取餐
[INFO] [1775809829.344946659] [order_food_server]: 反馈: 配送中... 60%
[INFO] [1775809830.846790187] [order_food_server]: 反馈: 配送中... 70%
[INFO] [1775809832.347788640] [order_food_server]: 反馈: 配送中... 80%
[INFO] [1775809833.849659209] [order_food_server]: 反馈: 配送中... 90%
[INFO] [1775809835.351530328] [order_food_server]: 反馈: 订单即将送达
[INFO] [1775809836.352956186] [order_food_server]: 订单完成: 麻辣烫 x3 已成功送达!

客户端:

[INFO] [1775809823.335414532] [order_food_client]: 正在下单: 麻辣烫 x3
[INFO] [1775809823.335756815] [order_food_client]: 连接到外卖服务端...
[INFO] [1775809823.337203682] [order_food_client]: 订单已被接受,开始配送...
[INFO] [1775809823.338025290] [order_food_client]: 订单状态: 商家正在确认订单 | 进度: 10% | 步骤: 商家已接单
[INFO] [1775809825.340743263] [order_food_client]: 订单状态: 商家正在准备食物 | 进度: 30% | 步骤: 食物准备中
[INFO] [1775809827.342897486] [order_food_client]: 订单状态: 骑手正在取餐 | 进度: 50% | 步骤: 骑手已取餐
[INFO] [1775809829.345177384] [order_food_client]: 订单状态: 配送中... 60% | 进度: 60% | 步骤: 配送中
[INFO] [1775809830.847058587] [order_food_client]: 订单状态: 配送中... 70% | 进度: 70% | 步骤: 配送中
[INFO] [1775809832.348039165] [order_food_client]: 订单状态: 配送中... 80% | 进度: 80% | 步骤: 配送中
[INFO] [1775809833.849894426] [order_food_client]: 订单状态: 配送中... 90% | 进度: 90% | 步骤: 配送中
[INFO] [1775809835.351751428] [order_food_client]: 订单状态: 订单即将送达 | 进度: 95% | 步骤: 即将送达
[INFO] [1775809836.354185069] [order_food_client]: 订单结果: 成功=True, 消息=麻辣烫 x3 已成功送达!, 总耗时=25.8分钟

3.动作的命令行操作

3.1 查看动作列表

ros2 action list

输入:

ros2 action list

输出:

/order_food

3.2 查看动作详情

ros2 action info [动作名称]

输入:

ros2 action info /order_food -t

输出:

Action: /order_food
Action clients: 0
Action servers: 1
    /order_food_server [learn_action_interface/action/OrderFood]

3.3 发送 动作目标

ros2 action send_goal [动作名称] [动作接口类型] [目标数据]

输入:

ros2 action send_goal /order_food learn_action_interface/action/OrderFood "{food_name: "麻辣烫", quantity: 5}" -f

输出:

Sending goal:
     food_name: 麻辣烫
quantity: 5

Goal accepted with ID: d16cf80ff96745a48ba6f14c1c138b5c

Feedback:
    status: 商家正在确认订单
progress_percent: 10
current_step: 商家已接单

Feedback:
    status: 商家正在准备食物
progress_percent: 30
current_step: 食物准备中

Feedback:
    status: 骑手正在取餐
progress_percent: 50
current_step: 骑手已取餐

Feedback:
    status: 配送中... 60%
progress_percent: 60
current_step: 配送中

Feedback:
    status: 配送中... 70%
progress_percent: 70
current_step: 配送中

Feedback:
    status: 配送中... 80%
progress_percent: 80
current_step: 配送中

Feedback:
    status: 配送中... 90%
progress_percent: 90
current_step: 配送中

Feedback:
    status: 订单即将送达
progress_percent: 95
current_step: 即将送达

Result:
    success: true
message: 麻辣烫 x5 已成功送达!
total_time: 10.07381534576416

Goal finished with status: SUCCEEDED