ROS2之DDS调优代码实例

上文我们介绍了DDS的内容,接下来我们会介绍DDS在实际开发中的应用

首先明确调优概念,调优是针对潜在的问题做优化,使结果更符合开发者的预期

以下是结合两个调优案例的具体分析,从调优目的优化表现潜在问题三个角度展开说明,帮助理解 DDS 通信调优的实际意义。


案例 1:机器人导航系统

调优目的

  1. 确保控制指令的实时性
    • 机器人运动控制指令(如速度、转向)需要极低延迟,否则可能导致机器人响应滞后甚至失控。
  2. 保证导航目标的可靠传递
    • 导航目标(如目标坐标)必须准确无误地传递到导航模块,否则任务无法启动或执行错误。
  3. 平衡反馈频率与资源占用
    • 高频反馈(如导航进度)可能导致网络拥塞,需在实时性和资源消耗之间权衡。

调优的“优”表现在哪里?

  • 控制指令(Topic)
    • 使用 BEST_EFFORT 降低延迟,避免因等待重传导致的指令滞后。
    • 小历史深度(如 depth=1)防止过时的控制指令堆积。
  • 导航目标(Action Goal)
    • 使用 RELIABLE 确保目标不丢失,TRANSIENT_LOCAL 保证新节点能获取历史目标。
  • 反馈(Action Feedback)
    • 使用 BEST_EFFORT 允许偶尔丢包,避免反馈阻塞主任务。

调优前可能存在的问题

  1. 控制指令延迟过高
    • 默认的 RELIABLE QoS 导致重传机制引入延迟,机器人运动不流畅。
  2. 导航目标丢失
    • 默认的 VOLATILE 持久性导致新加入的导航模块无法获取已发布的目标。
  3. 反馈数据占用过多带宽
    • 高频反馈使用 RELIABLE 模式,导致网络拥堵,影响控制指令的实时性。

案例 2:工业物联网(IIoT)

调优目的

  1. 保障设备状态的高可靠性
    • 设备状态(如故障报警)必须可靠传递,否则可能导致生产事故。
  2. 高效传输海量传感器数据
    • 传感器数据(如温度、压力)量大,需避免传输延迟或丢包。
  3. 适应资源受限环境
    • 工业设备可能计算能力有限,需减少通信开销。

调优的“优”表现在哪里?

  • 设备状态(Service)
    • 使用 RELIABLE 确保请求和响应不丢失,设置超时时间(如 500ms)防止服务端无响应。
  • 传感器数据(Topic)
    • 启用 零拷贝(Zero-Copy) 减少内存复制开销,提升传输效率。
    • 调整 DDS 缓冲区大小,支持大数据分片传输。
  • 资源优化
    • 选择轻量级 DDS 实现(如 Cyclone DDS),降低 CPU 和内存占用。

调优前可能存在的问题

  1. 设备状态丢失
    • 默认的 BEST_EFFORT QoS 导致关键报警信号丢失,无法及时处理故障。
  2. 传感器数据传输卡顿
    • 默认的小缓冲区无法处理大数据量,导致分片丢失或重传。
  3. 资源耗尽
    • 未经优化的 DDS 实现占用过多 CPU 和内存,导致工业设备性能下降。

调优的核心目标总结

调优方向具体表现潜在问题(未调优时)
实时性降低延迟(如控制指令)、减少阻塞(如反馈)指令延迟 → 机器人响应慢
可靠性确保关键数据不丢失(如导航目标、设备状态)目标丢失 → 任务失败;报警丢失 → 生产事故
资源效率减少内存/CPU 占用(如限制历史深度、选择轻量级 DDS)资源耗尽 → 系统崩溃
带宽利用率平衡数据量与传输速率(如零拷贝、分片传输)网络拥塞 → 数据传输卡顿
业务场景适配性根据需求选择 QoS 组合(如高频反馈用 BEST_EFFORT,关键数据用 RELIABLE一刀切配置 → 性能与需求不匹配

如何判断是否需要调优?

如果出现以下现象,可能需要对 DDS 通信进行调优:

  1. 功能性问题
    • 数据丢失(如导航目标收不到)、服务超时(如设备状态请求无响应)。
  2. 性能瓶颈
    • 延迟过高(如控制指令滞后)、带宽占用率满载。
  3. 资源异常
    • CPU/内存占用率飙升、节点频繁崩溃。
  4. 业务需求变化
    • 新增高频率传感器、升级实时性要求。

调优的本质

DDS 调优的最终目标是:在满足业务需求的前提下,以最小的资源消耗实现最佳的通信性能。它不是简单的“参数调整”,而是对以下三者的动态平衡:

  1. 通信机制特性(Topic/Service/Action 的差异)
  2. 业务场景需求(实时性、可靠性、数据量)
  3. 系统资源限制(CPU、内存、网络带宽)

通过调优,可以解决 ROS 2 默认配置与具体场景不匹配的问题,从而提升系统的稳定性、效率和可靠性。

接下来是一个完整的 机器人导航系统 C++ 代码示例,包含控制指令发布者、订阅者、导航动作服务器和客户端,并集成 QoS 调优配置。代码分为三个节点,注释会详细说明每个模块的功能和调优逻辑。

注意:一个 ROS 2 节点可以同时支持多种通信类型

代码结构

  1. 控制指令发布者节点 (control_publisher)
  2. 控制指令订阅者 + 导航客户端节点 (hybrid_subscriber_client)
  3. 导航动作服务器节点 (navigation_action_server)

1. 控制指令发布者节点 (Publisher)

// control_publisher.cpp
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/qos.hpp"

class ControlPublisher : public rclcpp::Node {
public:
  ControlPublisher() : Node("control_publisher") {
    // QoS 调优:BEST_EFFORT + 历史深度1,优化实时性
    auto qos = rclcpp::QoS(rclcpp::KeepLast(1))
      .reliability(rclcpp::ReliabilityPolicy::BestEffort);

    // 创建 Publisher,发布到 "/cmd_vel"
    publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", qos);

    // 定时器:10Hz 发布控制指令
    timer_ = this->create_wall_timer(
      std::chrono::milliseconds(100),
      [this]() {
        auto msg = geometry_msgs::msg::Twist();
        msg.linear.x = 0.6;  // 设置线速度
        msg.angular.z = 0.0;
        publisher_->publish(msg);
        RCLCPP_INFO(this->get_logger(), "控制指令发布: 线速度=%.2f", msg.linear.x);
      }
    );
  }

private:
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
};

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

2. 混合节点:订阅者 + 导航客户端 (Subscriber + Action Client)

// hybrid_subscriber_client.cpp
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "nav2_msgs/action/navigate_to_pose.hpp"

using NavigateToPose = nav2_msgs::action::NavigateToPose;
using GoalHandle = rclcpp_action::ClientGoalHandle<NavigateToPose>;

class HybridNode : public rclcpp::Node {
public:
  HybridNode() : Node("hybrid_subscriber_client") {
    // ---------------------- 订阅者配置 ----------------------
    // 匹配发布者的 QoS:BEST_EFFORT + 历史深度1
    auto sub_qos = rclcpp::QoS(rclcpp::KeepLast(1))
      .reliability(rclcpp::ReliabilityPolicy::BestEffort);

    subscription_ = this->create_subscription<geometry_msgs::msg::Twist>(
      "/cmd_vel",
      sub_qos,
      [this](const geometry_msgs::msg::Twist::SharedPtr msg) {
        RCLCPP_INFO(this->get_logger(), "收到控制指令: 线速度=%.2f", msg->linear.x);
        if (msg->linear.x > 0.5) {
          send_navigation_goal();  // 触发导航动作
        }
      }
    );

    // ---------------------- Action 客户端配置 ----------------------
    action_client_ = rclcpp_action::create_client<NavigateToPose>(this, "navigate_to_pose");
  }

private:
  void send_navigation_goal() {
    if (!action_client_->wait_for_action_server(std::chrono::seconds(2))) {
      RCLCPP_ERROR(this->get_logger(), "导航服务未就绪");
      return;
    }

    auto goal_msg = NavigateToPose::Goal();
    goal_msg.pose.header.frame_id = "map";
    goal_msg.pose.pose.position.x = 5.0;  // 目标位置

    // 配置 Action 的 QoS(与服务端匹配)
    auto send_options = rclcpp_action::Client<NavigateToPose>::SendGoalOptions();
    send_options.feedback_callback = 
      [this](GoalHandle::SharedPtr, const std::shared_ptr<const NavigateToPose::Feedback> feedback) {
        RCLCPP_INFO(this->get_logger(), "导航进度: X=%.2f", feedback->current_pose.pose.position.x);
      };
    send_options.result_callback = 
      [this](const GoalHandle::WrappedResult& result) {
        if (result.code == rclcpp_action::ResultCode::SUCCEEDED) {
          RCLCPP_INFO(this->get_logger(), "导航成功!");
        } else {
          RCLCPP_ERROR(this->get_logger(), "导航失败");
        }
      };

    action_client_->async_send_goal(goal_msg, send_options);
    RCLCPP_INFO(this->get_logger(), "导航目标已发送");
  }

  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription_;
  rclcpp_action::Client<NavigateToPose>::SharedPtr action_client_;
};

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

3. 导航动作服务器节点 (Action Server)

// navigation_action_server.cpp
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "nav2_msgs/action/navigate_to_pose.hpp"
#include "rclcpp/qos.hpp"

using NavigateToPose = nav2_msgs::action::NavigateToPose;
using GoalHandle = rclcpp_action::ServerGoalHandle<NavigateToPose>;

class NavigationActionServer : public rclcpp::Node {
public:
  NavigationActionServer() : Node("navigation_action_server") {
    // ---------------------- Action 服务端 QoS 调优 ----------------------
    // Goal QoS:RELIABLE + TRANSIENT_LOCAL
    auto goal_qos = rclcpp::QoS(rclcpp::KeepLast(10))
      .reliability(rclcpp::ReliabilityPolicy::Reliable)
      .durability(rclcpp::DurabilityPolicy::TransientLocal);

    // Feedback QoS:BEST_EFFORT
    auto feedback_qos = rclcpp::QoS(rclcpp::KeepLast(1))
      .reliability(rclcpp::ReliabilityPolicy::BestEffort);

    // 创建 Action Server
    action_server_ = rclcpp_action::create_server<NavigateToPose>(
      this,
      "navigate_to_pose",
      [this](const rclcpp_action::GoalUUID&, auto&& goal) {
        RCLCPP_INFO(this->get_logger(), "收到导航目标: X=%.2f", goal->pose.pose.position.x);
        return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
      },
      [this](auto&& goal_handle) {
        RCLCPP_INFO(this->get_logger(), "导航任务取消");
        return rclcpp_action::CancelResponse::ACCEPT;
      },
      [this](auto&& goal_handle) {
        std::thread{std::bind(&NavigationActionServer::execute, this, goal_handle)}.detach();
      },
      goal_qos,  // 应用 QoS 配置
      feedback_qos
    );
  }

private:
  void execute(const std::shared_ptr<GoalHandle> goal_handle) {
    auto feedback = std::make_shared<NavigateToPose::Feedback>();
    auto result = std::make_shared<NavigateToPose::Result>();

    // 模拟导航过程(每秒更新一次进度)
    for (int i = 1; i <= 10; ++i) {
      feedback->current_pose.pose.position.x = i * 0.5;
      goal_handle->publish_feedback(feedback);
      RCLCPP_INFO(this->get_logger(), "导航中... 进度: %d%%", i * 10);
      std::this_thread::sleep_for(std::chrono::seconds(1));
    }

    result->result = "目标已到达";
    goal_handle->succeed(result);
  }

  rclcpp_action::Server<NavigateToPose>::SharedPtr action_server_;
};

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

编译配置 (CMakeLists.txt)

cmake_minimum_required(VERSION 3.8)
project(robot_navigation_system)

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(nav2_msgs REQUIRED)

# 控制指令发布者
add_executable(control_publisher src/control_publisher.cpp)
ament_target_dependencies(control_publisher
  rclcpp
  geometry_msgs
)

# 混合节点(订阅者 + 客户端)
add_executable(hybrid_subscriber_client src/hybrid_subscriber_client.cpp)
ament_target_dependencies(hybrid_subscriber_client
  rclcpp
  rclcpp_action
  geometry_msgs
  nav2_msgs
)

# 导航动作服务器
add_executable(navigation_action_server src/navigation_action_server.cpp)
ament_target_dependencies(navigation_action_server
  rclcpp
  rclcpp_action
  nav2_msgs
)

install(TARGETS
  control_publisher
  hybrid_subscriber_client
  navigation_action_server
  DESTINATION lib/${PROJECT_NAME}
)

ament_package()

系统运行流程

  1. 启动节点

    # 终端1: 启动控制指令发布者
    ros2 run robot_navigation_system control_publisher
    
    # 终端2: 启动导航动作服务器
    ros2 run robot_navigation_system navigation_action_server
    
    # 终端3: 启动混合节点(订阅者 + 客户端)
    ros2 run robot_navigation_system hybrid_subscriber_client
    
  2. 行为验证

    • 控制指令发布者持续发送线速度为 0.6 的指令。
    • 混合节点检测到线速度超过 0.5 时,自动发送导航目标。
    • 导航服务器执行任务并反馈进度,最终返回结果。

QoS 调优总结

模块QoS 配置优化目标
控制指令 (Topic)BestEffort + KeepLast(1)最小化延迟,允许丢包
导航目标 (Action Goal)Reliable + TransientLocal确保目标可靠传递
导航反馈 (Action Feedback)BestEffort + KeepLast(1)避免反馈阻塞主任务

通过此代码,读者可以实现一个完整的机器人导航系统,同时掌握 ROS 2 中多通信类型集成和 QoS 调优的核心方法。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值