ros2中Qos的C++配置方法

1. dds_debug.hpp

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
#ifndef DDS_DEBUG__DDS_DEBUG_HPP_
#define DDS_DEBUG__DDS_DEBUG_HPP_
 
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/qos.hpp>
#include <rmw/types.h>
#include <sensor_msgs/msg/imu.hpp>
 
const rmw_qos_profile_t my_custom_qos_profile =
{
    RMW_QOS_POLICY_HISTORY_KEEP_LAST,
    10,
    RMW_QOS_POLICY_RELIABILITY_RELIABLE,
    RMW_QOS_POLICY_DURABILITY_VOLATILE,
    RMW_DURATION_INFINITE,
    RMW_DURATION_INFINITE,
    RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
    RMW_DURATION_INFINITE,
    false
};
 
class DDS_debug : public rclcpp::Node
{
public:
    explicit DDS_debug();
    ~DDS_debug();
 
protected:
    void on_timer();
 
private:
    unsigned int cnt;
    rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr imu_pub_;
    rclcpp::TimerBase::SharedPtr timer_;
};
 
#endif

 2. dds_debug.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
#include "dds_debug/dds_debug.hpp"
 
DDS_debug::DDS_debug()
    : Node("dds_debug")
    , cnt(0)
{
    auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(my_custom_qos_profile), my_custom_qos_profile);
 
    imu_pub_ = create_publisher<sensor_msgs::msg::Imu>("/sensing/imu/tamagawa/imu_raw", qos);
     
    constexpr double period_s = 0.1;
    constexpr std::chrono::nanoseconds period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::duration<double>(period_s));
    timer_ = rclcpp::create_timer(this, get_clock(), period_ns, std::bind(&DDS_debug::on_timer, this));
}
 
DDS_debug::~DDS_debug() {}
 
void DDS_debug::on_timer() {
    cnt++;
    if (cnt <= 50) {
        sensor_msgs::msg::Imu imu_msg;
        imu_pub_->publish(imu_msg);
    }
}

 3. dds_debug_node.cpp

1
2
3
4
5
6
7
8
9
#include "dds_debug/dds_debug.hpp"
 
int main(int argc, char** argv) { 
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<DDS_debug>());
  rclcpp::shutdown();
 
  return 0;
}

 

posted @   rzy_up  阅读(296)  评论(0编辑  收藏  举报
相关博文:
阅读排行:
· 无需6万激活码!GitHub神秘组织3小时极速复刻Manus,手把手教你使用OpenManus搭建本
· C#/.NET/.NET Core优秀项目和框架2025年2月简报
· Manus爆火,是硬核还是营销?
· 一文读懂知识蒸馏
· 终于写完轮子一部分:tcp代理 了,记录一下
历史上的今天:
2021-03-14 MATLAB中元胞数组(Cell Array)
点击右上角即可分享
微信分享提示