ROS2 Topic 传输机制:板内 vs 跨板

ROS2 Topic 传输机制:板内 vs 跨板

1. 两种传输方式

2. 传输决策逻辑

场景 传输方式 是否反序列化
同进程同节点 Intra-Process (Zero-Copy) ❌ 不需要
同进程不同节点 Intra-Process ❌ 不需要
不同进程 DDS (UDP/TCP/Shared Memory) ✅ 需要
不同板块 DDS (网络) ✅ 需要

3. Intra-Process (板内) 传输原理

核心特性

  • 使用 IntraProcessBuffer 直接传递消息指针
  • 无需反序列化,消息以 ROS 消息对象形式传递
  • Zero-Copy:发布者直接将消息存入订阅者的缓冲区

源码分析

cpp 复制代码
// intra_process_buffer.hpp
// 板内传输:直接传递 shared_ptr,不经过序列化/反序列化

// 添加消息到缓冲区(共享方式)
virtual void add_shared(MessageSharedPtr msg)  
{
  buffer_->enqueue(std::move(shared_msg));  // 直接存入指针
}

// 从缓冲区消费消息
virtual MessageSharedPtr consume_shared()
{
  return buffer_->dequeue();  // 直接取出指针,无拷贝
}

传输流程

复制代码
Publisher::publish()
    ↓
IntraProcessManager::match_publishers_to_subscriptions()
    ↓
IntraProcessBuffer::add_shared(msg)  // 直接存入订阅者缓冲区
    ↓
订阅者通过 wait() 收到通知,直接取用消息对象

关键代码位置

  • rclcpp/experimental/intra_process_manager.hpp - 进程内通信管理器
  • rclcpp/experimental/buffers/intra_process_buffer.hpp - 进程内缓冲区
  • rclcpp/intra_process_setting.hpp - 进程内通信配置

4. DDS 传输 (跨板) 原理

需要反序列化的原因

  • DDS 层使用 CDR (Common Data Representation) 序列化
  • 数据在网络上以字节流传输
  • 订阅端必须反序列化为 ROS 消息对象

传输流程

复制代码
Publisher::publish()
    ↓
rmw_publish()  // 序列化: ROS Msg → CDR bytes
    ↓
RMW (FastDDS/CycloneDDS)
    ↓
网络传输 (UDP/TCP/Shmem)
    ↓
Subscription::take()  // 反序列化: CDR bytes → ROS Msg
    ↓
回调函数收到消息对象

5. use_intra_process_comms 配置场景

场景1: use_intra_process_comms = true

问题: 既有板内订阅,又有跨板订阅,Topic 默认用什么方式传输?

复制代码
┌─────────────────────────────────────────────────────────────────────┐
│  use_intra_process_comms = true                                     │
├─────────────────────────────────────────────────────────────────────┤
│                                                                     │
│  Publisher                                                          │
│     │                                                               │
│     ├──► 板内订阅A ──► Intra-Process (Zero-Copy, 无序列化)             │
│     │                                                               │
│     └──► 跨板订阅B ──► DDS (需序列化)                                  │
│                                                                     │
└─────────────────────────────────────────────────────────────────────┘

答案: 同时使用两种方式

  • 板内订阅Intra-Process (Zero-Copy,无序列化)
  • 跨板订阅DDS (需要序列化)

Publisher 会双重发布

  1. 一份通过 IntraProcessManager 发给板内订阅者
  2. 一份通过 DDS/RMW 发给跨板订阅者

源码逻辑

sub

cpp 复制代码
// IntraProcessManager 会检查匹配的订阅者
// 如果存在跨进程的订阅者,仍然会走 DDS 路径
if (can_communicate(publisher, subscription)) {
  // 板内通信:IntraProcessBuffer
} else {
  // 跨进程通信:DDS
}

pub

cpp 复制代码
publish(std::unique_ptr<T, ROSMessageTypeDeleter> msg)
  {
    if (!intra_process_is_enabled_) {
      this->do_inter_process_publish(*msg);
      return;
    }
    // If an interprocess subscription exist, then the unique_ptr is promoted
    // to a shared_ptr and published.
    // This allows doing the intraprocess publish first and then doing the
    // interprocess publish, resulting in lower publish-to-subscribe latency.
    // It's not possible to do that with an unique_ptr,
    // as do_intra_process_publish takes the ownership of the message.

    // When durability is set to TransientLocal (i.e. there is a buffer),
    // inter process publish should always take place to ensure
    // late joiners receive past data.
    bool inter_process_publish_needed =
      get_subscription_count() > get_intra_process_subscription_count() || buffer_;

    if (inter_process_publish_needed) {
      auto shared_msg =
        this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg));
      if (buffer_) {
        buffer_->add_shared(shared_msg);
      }
      this->do_inter_process_publish(*shared_msg);
    } else {
      if (buffer_) {
        auto shared_msg =
          this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg));
        buffer_->add_shared(shared_msg);
      } else {
        this->do_intra_process_ros_message_publish(std::move(msg));
      }
    }
  }

场景2: use_intra_process_comms = false

问题: 关闭后,板内和板间都有订阅,板内需要反序列化吗?

复制代码
┌─────────────────────────────────────────────────────────────────────┐
│  use_intra_process_comms = false                                   │
├─────────────────────────────────────────────────────────────────────┤
│                                                                     │
│  Publisher                                                        │
│     │                                                              │
│     ├──► 板内订阅A ──► DDS (需序列化) ◄── 需要反序列化!          │
│     │                                                              │
│     └──► 跨板订阅B ──► DDS (需序列化) ◄── 需要反序列化           │
│                                                                     │
└─────────────────────────────────────────────────────────────────────┘

答案: 需要反序列化

关闭 Intra-Process 后,所有订阅都走 DDS

  1. 序列化:ROS Msg → CDR bytes
  2. 本地回环或网络传输
  3. 反序列化:CDR bytes → ROS Msg

即使是同一个板内的订阅,也需要完整的序列化/反序列化过程。


6. 对比总结

配置 板内订阅 跨板订阅 序列化/反序列化
use_intra_process_comms=true Intra-Process ✅ DDS 跨板需要
use_intra_process_comms=false DDS DDS 都需要

7. 性能影响

场景 延迟 备注
true + 板内 ~1μs Zero-Copy,最优
true + 跨板 ~100μs DDS 序列化
false + 板内 ~100μs 吃大亏! 绕道 DDS
false + 跨板 ~100μs 正常 DDS

8. 如何启用 Intra-Process

方式1: Node 级别默认启用

cpp 复制代码
rclcpp::NodeOptions options;
options.use_intra_process_comms(true);  // 默认 true
auto node = std::make_shared<rclcpp::Node>("my_node", options);

方式2: Publisher/Subscriber 级别控制

cpp 复制代码
// 显式启用
auto pub = node->create_publisher<std_msgs::msg::String>(
  "topic",
  rclcpp::QoS(10),
  rclcpp::IntraProcessSetting::Enable  // 显式启用
);

// 显式禁用(强制走 DDS)
auto pub2 = node->create_publisher<std_msgs::msg::String>(
  "topic",
  rclcpp::QoS(10),
  rclcpp::IntraProcessSetting::Disable  // 强制 DDS
);

IntraProcessSetting 枚举

cpp 复制代码
enum class IntraProcessSetting
{
  Enable,     // 显式启用进程内通信
  Disable,    // 显式禁用进程内通信
  NodeDefault // 跟随 Node 的默认设置
};

9. Zero-Copy 优化

我们生成的优化文件 optimized_message_pool.hpp 进一步优化了消息传递:

cpp 复制代码
// Zero-Copy 消息池
class OptimizedMessagePool {
public:
  // 预分配消息缓冲区
  // 指针直接复用
  // 减少内存分配/释放开销
  
  MessageT* allocate();    // 从池中获取
  void deallocate(MessageT* msg);  // 归还到池
};

10. 配置建议

推荐配置

cpp 复制代码
// ✅ 推荐:保持默认启用 intra-process
rclcpp::NodeOptions options;
options.use_intra_process_comms(true);  // 默认就是 true

何时禁用

只有在下述情况才考虑禁用:

cpp 复制代码
// 场景1:明确知道只需要跨板通信,不需要板内通信
rclcpp::NodeOptions options;
options.use_intra_process_comms(false);

// 场景2:调试时需要抓包分析 DDS 流量
// 禁用后所有流量都走 DDS,可以用 Wireshark 观察

⚠️ 注意事项

  • 禁用 use_intra_process_comms 不会让板内订阅"变快"
  • 反而会强制走 DDS 路径,增加不必要的序列化开销
  • 如果可能存在跨板订阅,禁用会损失性能

11. 总结

  1. 板内订阅 (Intra-Process)

    • Zero-Copy,无需序列化/反序列化
    • 延迟极低 (~1μs)
    • 消息以 shared_ptr 形式直接传递
  2. 跨板订阅 (DDS)

    • 需要 CDR 序列化/反序列化
    • 延迟较高 (~100μs+)
    • 支持跨进程、跨机器通信
  3. use_intra_process_comms = true:

    • 板内:Zero-Copy,无序列化
    • 跨板:DDS 序列化
    • 同时支持两种路径
  4. use_intra_process_comms = false:

    • 全部走 DDS
    • 板内也需要反序列化
    • 性能最差
  5. 默认行为

    • ROS2 默认启用 Intra-Process
    • 系统自动选择最优传输路径
相关推荐
小手智联老徐29 分钟前
ROS2:Humble 安装详解(Ubuntu 22.04)
ros2·humble·colcon
弹简特4 小时前
【JavaSE-网络部分06】TCP 纯高性能优化机制:延迟应答・捎带应答【传输层】
网络·tcp/ip·性能优化·捎带应答·延迟应答
chenglin0165 小时前
AI应用性能优化与生产环境部署
人工智能·性能优化
We་ct5 小时前
JS手撕:性能优化、渲染技巧与定时器实现
开发语言·前端·javascript·面试·性能优化·定时器·性能
刚子编程6 小时前
.NET 8 性能优化实战:让你的应用起飞
性能优化·.net
rqtz6 小时前
【机器人】ROS2 功能包创建与 CMake 编译链路探秘
机器人·cmake·ros2
Dontla7 小时前
Profiling(性能分析)介绍(用数据驱动性能优化)
性能优化
weixin199701080161 天前
《中国供应商商品详情页前端性能优化实战》
前端·性能优化
maxmaxma1 天前
ROS2机器人少年创客营:Python第三课
开发语言·python·机器人·ros2
yungcy61631 天前
React性能优化实战:从卡顿到丝滑,15个核心技巧覆盖全场景
前端·react.js·性能优化