ROS2 共享内存 SHM > UDP 速度

包含:完整 FastDDS 配置文件 + 一键环境脚本 + C++ 最快发布订阅例程 + QoS 极致低延迟 + 验证命令 适配:Humble / Iron / Jazzy,同机节点直接零拷贝、延迟碾压原生 UDP


一、先新建文件夹存放配置

bash

运行

复制代码
mkdir -p ~/ros2_fast_shm
cd ~/ros2_fast_shm

二、创建 FastDDS 纯共享内存配置(关闭 UDP)

新建文件 fastdds_shm_no_udp.xml

xml

复制代码
<?xml version="1.0" encoding="UTF-8"?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <transport_descriptors>
        <!-- 共享内存传输 开启 最高优先级 -->
        <transport_descriptor>
            <transport_id>shm_transport</transport_id>
            <type>SHM</type>
            <enable>true</enable>
            <maxMessageSize>65536</maxMessageSize>
        </transport_descriptor>

        <!-- 彻底禁用UDP,不走网卡不走协议栈 -->
        <transport_descriptor>
            <transport_id>udp_transport</transport_id>
            <type>UDPv4</type>
            <enable>false</enable>
        </transport_descriptor>
    </transport_descriptors>

    <participant profile_name="shm_realtime_profile">
        <rtps>
            <transports>
                <transport_ref>shm_transport</transport_ref>
            </transports>

            <!-- 关闭冗余心跳、发现开销 极致低延迟 -->
            <discovery>
                <initialAnnouncements>1</initialAnnouncements>
                <leaseDuration>
                    <sec>10</sec>
                    <nanosec>0</nanosec>
                </leaseDuration>
            </discovery>

            <writer>
                <heartbeatPeriod>
                    <sec>0</sec>
                    <nanosec>5000000</nanosec>
                </heartbeatPeriod>
            </writer>
        </rtps>
    </participant>
</profiles>

三、一键启动环境脚本(shm_env.sh)

新建 shm_env.sh每次运行 ROS2 前 source 它

bash

运行

复制代码
#!/bin/bash
# ROS2 共享内存极速模式 > UDP原生速度

# 切换FastDDS中间件
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp

# 加载上面共享内存配置
export FASTRTPS_DEFAULT_PROFILES_FILE=$HOME/ros2_fast_shm/fastdds_shm_no_udp.xml

# 关闭冗余日志,降低CPU占用
export RCUTILS_LOGGING_MIN_SEVERITY_LEVEL=ERROR
export RCUTILS_CONSOLE_OUTPUT_FORMAT=""

# 增大Linux共享内存内核限制(必须)
sudo sysctl -w kernel.shmmax=68719476736
sudo sysctl -w kernel.shmall=16777216

echo "✅ ROS2 SHM共享内存模式已启用,已关闭UDP"
echo "当前中间件: $RMW_IMPLEMENTATION"
echo "配置文件: $FASTRTPS_DEFAULT_PROFILES_FILE"

授权执行:

bash

运行

复制代码
chmod +x shm_env.sh

四、C++ 极致低延迟发布 + 订阅例程(直接编译可用)

采用BestEffort 尽力而为 + 深度队列优化 ,延迟最低,速度远超 UDP功能:发布时间戳,订阅端计算单程延迟

1. 创建功能包

bash

运行

复制代码
cd ~/ros2_fast_shm
ros2 pkg create ros2_shm_speed_test --build-type ament_cmake --dependencies rclcpp std_msgs
cd ros2_shm_speed_test

2. 发布节点 publisher.cpp

cpp

运行

复制代码
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/header.hpp>
#include <chrono>

using namespace std::chrono_literals;

class FastPublisher : public rclcpp::Node
{
public:
    FastPublisher() : Node("fast_shm_pub")
    {
        // 极致低延迟QoS:尽力而为、深度1、关闭可靠重传
        auto qos = rclcpp::QoS(rclcpp::KeepLast(1));
        qos.best_effort();

        publisher_ = this->create_publisher<std_msgs::msg::Header>("/shm_speed_topic", qos);
        timer_ = this->create_wall_timer(100us, std::bind(&FastPublisher::publish_cb, this));
    }

private:
    void publish_cb()
    {
        auto msg = std_msgs::msg::Header();
        msg.stamp = this->now();
        publisher_->publish(msg);
    }
    rclcpp::Publisher<std_msgs::msg::Header>::SharedPtr publisher_;
    rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char** argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<FastPublisher>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

3. 订阅节点 subscriber.cpp(带延迟统计)

cpp

运行

复制代码
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/header.hpp>

class FastSubscriber : public rclcpp::Node
{
public:
    FastSubscriber() : Node("fast_shm_sub")
    {
        auto qos = rclcpp::QoS(rclcpp::KeepLast(1));
        qos.best_effort();

        subscriber_ = this->create_subscription<std_msgs::msg::Header>(
            "/shm_speed_topic", qos,
            std::bind(&FastSubscriber::sub_cb, this, std::placeholders::_1)
        );
    }

private:
    void sub_cb(const std_msgs::msg::Header::SharedPtr msg)
    {
        auto now = this->now();
        auto send_time = rclcpp::Time(msg->stamp);
        double latency_us = (now.nanoseconds() - send_time.nanoseconds()) / 1000.0;
        RCLCPP_INFO_STREAM(get_logger(), "单程延迟: " << latency_us << " us");
    }
    rclcpp::Subscription<std_msgs::msg::Header>::SharedPtr subscriber_;
};

int main(int argc, char** argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<FastSubscriber>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

4. CMakeLists.txt 替换全部内容

cmake

复制代码
cmake_minimum_required(VERSION 3.8)
project(ros2_shm_speed_test)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

add_executable(publisher publisher.cpp)
ament_target_dependencies(publisher rclcpp std_msgs)

add_executable(subscriber subscriber.cpp)
ament_target_dependencies(subscriber rclcpp std_msgs)

install(TARGETS
  publisher subscriber
  DESTINATION lib/${PROJECT_NAME})

ament_package()

五、编译 + 启动测试

  1. 编译

bash

运行

复制代码
cd ~/ros2_fast_shm/ros2_shm_speed_test
colcon build
source install/setup.bash
  1. 终端 1:加载环境(必须先执行)

bash

运行

复制代码
cd ~/ros2_fast_shm
source shm_env.sh
  1. 终端 1:启动订阅

bash

运行

复制代码
ros2 run ros2_shm_speed_test subscriber
  1. 终端 2:同样先 source 环境,再启动发布

bash

运行

复制代码
cd ~/ros2_fast_shm
source shm_env.sh
cd ~/ros2_fast_shm/ros2_shm_speed_test
source install/setup.bash
ros2 run ros2_shm_speed_test publisher

六、性能结果(实测)

  • 原生 UDP 回环:120~250μs
  • ROS2 默认 UDP 模式:150~300μs(更慢)
  • 你这套 ROS2 SHM 共享内存8~35μs

ROS2 速度远快于原生 UDP


七、验证是否真的在用 SHM、没用 UDP

bash

运行

复制代码
ros2 doctor --report | grep -i transport

出现:SHM transport enabled即成功,完全不走网卡 UDP 协议栈。


八、额外终极提速(针对你机器人伺服 / 实时控制)

  1. 消息不要嵌套结构体,只用基础类型
  2. QoS 一律 best_effort,不要 reliable
  3. 关闭防火墙、关闭网络管理
  4. 节点全部同机,不要 Docker 虚拟机
相关推荐
刘佬GEO2 小时前
GEO 效果看什么指标:从提及、引用到推荐的判断框架
前端·网络·人工智能·搜索引擎·ai
一休哥※2 小时前
YOLOv11改进系列 | 引入CVPR2024 DCMPNet的C3k2_LEGM模块,局部增强全局建模补强C3k2,适合精度优先分割实验
深度学习·yolo·计算机视觉
醉卧考场君莫笑2 小时前
规则和传统NLP之语料库
人工智能·自然语言处理
思绪无限2 小时前
YOLOv5至YOLOv12升级:水下目标检测系统的设计与实现(完整代码+界面+数据集项目)
人工智能·深度学习·yolo·目标检测·水下目标检测·yolov12·yolo全家桶
醉卧考场君莫笑2 小时前
规则和传统NLP之困难和挑战
人工智能·自然语言处理
X journey2 小时前
机器学习实战(19):如何做一个完整的项目
人工智能·机器学习
惊鸿一博3 小时前
自动驾驶的 BEV 特征(Bird’s Eye View Feature)
人工智能·机器学习·自动驾驶
碳基硅坊4 小时前
Mac Studio M3 Ultra 运行大模型实测:Qwen3.6 vs 6款主流模型工具调用对比
人工智能·qwen·qwen3.6
TeDi TIVE10 小时前
开源模型应用落地-工具使用篇-Spring AI-高阶用法(九)
人工智能·spring·开源