ROS2 通信机制详解:Topic、Service、Action 区别与使用场景

概述

ROS2 提供了三种核心的节点间通信机制,分别适用于不同的数据传输场景:

  • Topic(话题):发布/订阅模型,用于持续性的单向数据流。
  • Service(服务):请求/响应模型,用于需要即时返回结果的短时操作。
  • Action(动作):带反馈与取消功能的任务模型,用于长时间运行且可监控进度的任务。

理解它们的差异并正确选用,是开发机器人软件系统的重要基础。

sequenceDiagram
    participant Pub as 发布者
    participant Sub as 订阅者
    Note over Pub,Sub: Topic 模式
    Pub->>Sub: 消息1(异步流)
    Pub->>Sub: 消息2
    Pub->>Sub: 消息3

    participant Client as 客户端
    participant Server as 服务端
    Note over Client,Server: Service 模式
    Client->>Server: 请求
    Server-->>Client: 响应(同步等待)

    participant ActClient as 动作客户端
    participant ActServer as 动作服务器
    Note over ActClient,ActServer: Action 模式
    ActClient->>ActServer: 发送目标
    ActServer-->>ActClient: 反馈(进度)
    ActServer-->>ActClient: 反馈...
    ActServer-->>ActClient: 最终结果
    ActClient-->>ActServer: 可随时发送取消指令

一、Topic(话题)—— 持续的数据流

1.1 通信模型

Topic 采用发布/订阅模型,发布者将消息发送到指定话题,所有订阅了该话题的节点都会异步收到数据。这种通信是单向的、支持多对多关系,发布者与订阅者之间相互解耦。典型应用包括激光雷达扫描、摄像头图像、关节角度等高频数据。

1.2 关键配置与注意事项

  • 新订阅者默认只能收到订阅后发布的消息。若需获取历史数据,可通过 QoS 配置 DurabilityTransient Local
  • 对可靠性有要求的数据,应将 QoS 中的 Reliability 设为 Reliable,默认的 Best Effort 可能导致丢帧。
  • 调试时可使用 ros2 topic echo 查看消息内容,ros2 topic hz 检查发布频率。

1.3 代码示例(C++)

温度发布者 temperature_publisher.cpp

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
#include <chrono>
#include <random>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/float32.hpp"

using namespace std::chrono_literals;

class TemperaturePublisher : public rclcpp::Node {
public:
TemperaturePublisher()
: Node("temp_pub") {
publisher_ = this->create_publisher<std_msgs::msg::Float32>("temperature", 10);
timer_ = this->create_wall_timer(
1s, std::bind(&TemperaturePublisher::publish_temperature, this));
}

private:
void publish_temperature() {
auto message = std_msgs::msg::Float32();
std::random_device rd;
std::mt19937 gen(rd());
std::uniform_real_distribution<float> dist(20.0f, 35.0f);
message.data = dist(gen);
publisher_->publish(message);
RCLCPP_INFO(this->get_logger(), "发布温度: %.2f°C", message.data);
}

rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<TemperaturePublisher>());
rclcpp::shutdown();
return 0;
}

报警订阅者 temperature_subscriber.cpp

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/float32.hpp"

class AlarmSubscriber : public rclcpp::Node {
public:
AlarmSubscriber()
: Node("alarm_sub") {
subscription_ = this->create_subscription<std_msgs::msg::Float32>(
"temperature", 10,
std::bind(&AlarmSubscriber::temperature_callback, this, std::placeholders::_1));
}

private:
void temperature_callback(const std_msgs::msg::Float32::SharedPtr msg) {
if (msg->data > 30.0f) {
RCLCPP_WARN(this->get_logger(), "高温警报!当前温度: %.2f°C", msg->data);
}
}

rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr subscription_;
};

int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<AlarmSubscriber>());
rclcpp::shutdown();
return 0;
}

二、Service(服务)—— 即时的请求与响应

2.1 通信模型

Service 基于客户端/服务器模型,是一种同步的远程过程调用(RPC)。客户端发送请求后会阻塞等待服务器返回响应,整个过程为一对一交互。适用于执行时间极短、需要即时确认的操作,如参数查询、功能开关等。

2.2 关键配置与注意事项

  • 服务端回调必须快速完成(通常毫秒级),否则会阻塞后续请求。
  • 多客户端并发请求时,服务器默认串行处理。若需并发处理,可通过多线程回调组实现。
  • 不应在服务回调中执行耗时计算或等待其他动作。

2.3 自定义服务与代码示例(C++)

定义 .srv 文件,例如 AddTwoInts.srv(可使用 example_interfaces/srv/AddTwoInts 直接测试):

1
2
3
4
int64 a
int64 b
---
int64 sum

服务器端实现:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"

class AddServer : public rclcpp::Node {
public:
AddServer()
: Node("add_server") {
service_ = this->create_service<example_interfaces::srv::AddTwoInts>(
"add_two_ints",
std::bind(&AddServer::add_callback, this, std::placeholders::_1, std::placeholders::_2));
}

private:
void add_callback(
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) {
response->sum = request->a + request->b;
RCLCPP_INFO(this->get_logger(), "收到请求: %ld + %ld = %ld",
request->a, request->b, response->sum);
}

rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service_;
};

int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<AddServer>());
rclcpp::shutdown();
return 0;
}

客户端调用示例:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"

using namespace std::chrono_literals;

class AddClient : public rclcpp::Node {
public:
AddClient()
: Node("add_client") {
client_ = this->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");
}

void call_service(int64_t a, int64_t b) {
while (!client_->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(this->get_logger(), "被中断,退出等待");
return;
}
RCLCPP_INFO(this->get_logger(), "等待服务上线...");
}

auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = a;
request->b = b;

auto future_result = client_->async_send_request(request);
if (rclcpp::spin_until_future_complete(this->get_node_base_interface(), future_result) ==
rclcpp::FutureReturnCode::SUCCESS) {
RCLCPP_INFO(this->get_logger(), "计算结果: %ld", future_result.get()->sum);
} else {
RCLCPP_ERROR(this->get_logger(), "服务调用失败");
}
}

private:
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
};

int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
auto node = std::make_shared<AddClient>();
node->call_service(3, 5);
rclcpp::shutdown();
return 0;
}

三、Action(动作)—— 可监控的长时间任务

3.1 通信模型

Action 专为耗时、可抢占、需要进度反馈的任务设计。它结合了 Topic 和 Service:Goal(目标)通过类似服务的方式发送,Feedback(反馈)通过话题持续发布,Result(结果)通过另一服务返回,同时支持随时取消。典型应用包括导航、抓取、路径规划等。

3.2 关键配置与注意事项

  • 服务器必须以非阻塞方式执行任务,并定期发布反馈,必要时配合多线程或状态机。
  • 客户端使用异步接口避免阻塞主线程。
  • 取消任务调用 goal_handle->cancel_async()

3.3 自定义 Action 与代码示例(C++)

定义 .action 文件,例如 NavigateToPose.action(实际常使用 nav2_msgs/action/NavigateToPose):

1
2
3
4
5
6
7
8
9
# Goal
geometry_msgs/PoseStamped target_pose
---
# Result
bool success
string status_message
---
# Feedback
float32 distance_remaining

客户端发送目标并接收反馈:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
#include "rclcpp/rclcpp.hpp"
#include "my_robot_interfaces/action/navigate_to_pose.hpp"
#include "rclcpp_action/rclcpp_action.hpp"

using NavigateToPose = my_robot_interfaces::action::NavigateToPose;
using GoalHandleNavigate = rclcpp_action::ClientGoalHandle<NavigateToPose>;

class NavClient : public rclcpp::Node {
public:
NavClient()
: Node("nav_client") {
client_ = rclcpp_action::create_client<NavigateToPose>(this, "navigate_to_pose");
}

void send_goal(const geometry_msgs::msg::PoseStamped & target_pose) {
if (!client_->wait_for_action_server(std::chrono::seconds(5))) {
RCLCPP_ERROR(this->get_logger(), "Action 服务器未上线");
return;
}

auto goal_msg = NavigateToPose::Goal();
goal_msg.target_pose = target_pose;

auto send_goal_options = rclcpp_action::Client<NavigateToPose>::SendGoalOptions();
send_goal_options.feedback_callback =
std::bind(&NavClient::feedback_callback, this, std::placeholders::_1, std::placeholders::_2);
send_goal_options.result_callback =
std::bind(&NavClient::result_callback, this, std::placeholders::_1);

client_->async_send_goal(goal_msg, send_goal_options);
}

private:
void feedback_callback(
GoalHandleNavigate::SharedPtr,
const std::shared_ptr<const NavigateToPose::Feedback> feedback) {
RCLCPP_INFO(this->get_logger(), "剩余距离: %.2f 米", feedback->distance_remaining);
}

void result_callback(const GoalHandleNavigate::WrappedResult & result) {
switch (result.code) {
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(), "导航成功");
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(), "导航终止");
break;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_INFO(this->get_logger(), "导航取消");
break;
default:
RCLCPP_ERROR(this->get_logger(), "未知结果码");
break;
}
}

rclcpp_action::Client<NavigateToPose>::SharedPtr client_;
};

int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
auto node = std::make_shared<NavClient>();
// 构造一个目标位姿,实际场景中从其他节点获取
geometry_msgs::msg::PoseStamped pose;
pose.header.frame_id = "map";
pose.pose.position.x = 1.0;
pose.pose.position.y = 2.0;
pose.pose.orientation.w = 1.0;
node->send_goal(pose);
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

四、对比总结

特性 Topic Service Action
通信模式 发布/订阅 请求/响应 目标/反馈/结果
方向 单向 双向(同步) 双向(异步)
耦合度 松耦合(多对多) 紧耦合(一对一) 中等耦合
时间特性 持续数据流 瞬间完成 长时间运行
可抢占
进度反馈
典型场景 传感器、状态数据 开关、配置查询 导航、抓取、规划
常用命令 ros2 topic ros2 service ros2 action

五、如何选择

  • 需要持续传输数据? —— 选 Topic
  • 需要立即获得确认且操作极短? —— 选 Service
  • 需要执行耗时任务、查看进度或中途取消? —— 选 Action

如果发现自己在用 Service 处理耗时任务,同时额外建了一个 Topic 来汇报进度,这种场景直接用 Action 封装会更加规范。

六、典型系统应用示例

一个移动机器人系统通常会组合使用这三种机制: 1. 激光雷达通过 scan 话题(Topic)持续发布数据。 2. 导航任务通过 Action 发送目标,接收进度反馈和最终结果,并支持取消。 3. 急停或模式切换等即时指令通过 Service 实现。 4. 电池、温度等状态信息由各节点通过 Topic 广播,供监控节点订阅。


代码基于 ROS2 Humble + C++17,编译需在 CMakeLists.txt 中添加对应依赖(如 rclcppstd_msgsexample_interfaces 或自定义接口包),并配置 find_packageament_target_dependencies,修改后执行 colcon build 并 source 环境即可。 ```