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 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176
| #include <rclcpp/rclcpp.hpp> #include <std_msgs/msg/string.hpp> #include <sensor_msgs/msg/laser_scan.hpp>
class QoSDemo : public rclcpp::Node { public: QoSDemo() : Node("qos_demo") { setup_qos_profiles(); create_publishers(); create_subscribers(); timer_ = this->create_wall_timer( std::chrono::milliseconds(100), std::bind(&QoSDemo::timer_callback, this)); RCLCPP_INFO(this->get_logger(), "QoS Demo node started"); }
private: void setup_qos_profiles() { reliable_qos_ = rclcpp::QoS(10) .reliability(RMW_QOS_RELIABILITY_RELIABLE) .durability(RMW_QOS_DURABILITY_TRANSIENT_LOCAL); best_effort_qos_ = rclcpp::QoS(10) .reliability(RMW_QOS_RELIABILITY_BEST_EFFORT) .durability(RMW_QOS_DURABILITY_VOLATILE); realtime_qos_ = rclcpp::QoS(1) .reliability(RMW_QOS_RELIABILITY_RELIABLE) .durability(RMW_QOS_DURABILITY_VOLATILE) .deadline(std::chrono::milliseconds(50)) .liveliness_lease_duration(std::chrono::milliseconds(100)); sensor_qos_ = rclcpp::QoS(5) .reliability(RMW_QOS_RELIABILITY_BEST_EFFORT) .durability(RMW_QOS_DURABILITY_VOLATILE) .history(RMW_QOS_HISTORY_KEEP_LAST); } void create_publishers() { reliable_publisher_ = this->create_publisher<std_msgs::msg::String>( "/qos/reliable", reliable_qos_); best_effort_publisher_ = this->create_publisher<std_msgs::msg::String>( "/qos/best_effort", best_effort_qos_); realtime_publisher_ = this->create_publisher<std_msgs::msg::String>( "/qos/realtime", realtime_qos_); sensor_publisher_ = this->create_publisher<sensor_msgs::msg::LaserScan>( "/qos/sensor", sensor_qos_); } void create_subscribers() { reliable_subscription_ = this->create_subscription<std_msgs::msg::String>( "/qos/reliable", reliable_qos_, std::bind(&QoSDemo::reliable_callback, this, std::placeholders::_1)); best_effort_subscription_ = this->create_subscription<std_msgs::msg::String>( "/qos/best_effort", best_effort_qos_, std::bind(&QoSDemo::best_effort_callback, this, std::placeholders::_1)); realtime_subscription_ = this->create_subscription<std_msgs::msg::String>( "/qos/realtime", realtime_qos_, std::bind(&QoSDemo::realtime_callback, this, std::placeholders::_1)); sensor_subscription_ = this->create_subscription<sensor_msgs::msg::LaserScan>( "/qos/sensor", sensor_qos_, std::bind(&QoSDemo::sensor_callback, this, std::placeholders::_1)); } void reliable_callback(const std_msgs::msg::String::SharedPtr msg) { RCLCPP_INFO(this->get_logger(), "Reliable: %s", msg->data.c_str()); } void best_effort_callback(const std_msgs::msg::String::SharedPtr msg) { RCLCPP_INFO(this->get_logger(), "Best Effort: %s", msg->data.c_str()); } void realtime_callback(const std_msgs::msg::String::SharedPtr msg) { auto now = this->now(); auto msg_time = msg->header.stamp; auto latency = (now - msg_time).nanoseconds() / 1000000.0; RCLCPP_INFO(this->get_logger(), "Realtime: %s (latency: %.2f ms)", msg->data.c_str(), latency); } void sensor_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg) { RCLCPP_INFO(this->get_logger(), "Sensor: %zu ranges", msg->ranges.size()); } void timer_callback() { auto now = this->now(); auto reliable_msg = std_msgs::msg::String(); reliable_msg.data = "Reliable message " + std::to_string(counter_); reliable_msg.header.stamp = now; reliable_publisher_->publish(reliable_msg); auto best_effort_msg = std_msgs::msg::String(); best_effort_msg.data = "Best effort message " + std::to_string(counter_); best_effort_msg.header.stamp = now; best_effort_publisher_->publish(best_effort_msg); auto realtime_msg = std_msgs::msg::String(); realtime_msg.data = "Realtime message " + std::to_string(counter_); realtime_msg.header.stamp = now; realtime_publisher_->publish(realtime_msg); auto sensor_msg = sensor_msgs::msg::LaserScan(); sensor_msg.header.stamp = now; sensor_msg.header.frame_id = "laser_frame"; sensor_msg.angle_min = -3.14159; sensor_msg.angle_max = 3.14159; sensor_msg.angle_increment = 0.0174533; sensor_msg.range_min = 0.1; sensor_msg.range_max = 10.0; sensor_msg.ranges.resize(360, 1.0); sensor_publisher_->publish(sensor_msg); counter_++; } rclcpp::QoS reliable_qos_; rclcpp::QoS best_effort_qos_; rclcpp::QoS realtime_qos_; rclcpp::QoS sensor_qos_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr reliable_publisher_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr best_effort_publisher_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr realtime_publisher_; rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr sensor_publisher_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr reliable_subscription_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr best_effort_subscription_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr realtime_subscription_; rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr sensor_subscription_; rclcpp::TimerBase::SharedPtr timer_; int counter_ = 0; };
int main(int argc, char *argv[]) { rclcpp::init(argc, argv); auto node = std::make_shared<QoSDemo>(); rclcpp::spin(node); rclcpp::shutdown(); return 0; }
|