Skip to content

Commit 07c2851

Browse files
ibrahimhroobBenedikt Mersch
andauthored
Use SensorDataQoS for lidar subscriptions (#37)
Switched from SystemDefaultsQoS to SensorDataQoS for both LaserScan and PointCloud2 subscriptions to ensure compatibility with sensor publishers using BEST_EFFORT reliability. This avoids QoS incompatibility errors when subscribing to topics. Co-authored-by: Benedikt Mersch <mersch@igg.uni-bonn.de>
1 parent 4ac3f9d commit 07c2851

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

ros/src/kinematic_icp_ros/nodes/online_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ OnlineNode ::OnlineNode(const rclcpp::NodeOptions &options) {
4646
RCLCPP_INFO_STREAM(node_->get_logger(),
4747
"Started in 2D scanner mode with topic: " << lidar_topic_);
4848
laser_scan_sub_ = node_->create_subscription<sensor_msgs::msg::LaserScan>(
49-
lidar_topic_, rclcpp::SystemDefaultsQoS(),
49+
lidar_topic_, rclcpp::SensorDataQoS(),
5050
[&](const sensor_msgs::msg::LaserScan::ConstSharedPtr &msg) {
5151
const sensor_msgs::msg::PointCloud2::ConstSharedPtr lidar_msg = [&]() {
5252
auto projected_scan = std::make_shared<sensor_msgs::msg::PointCloud2>();
@@ -60,7 +60,7 @@ OnlineNode ::OnlineNode(const rclcpp::NodeOptions &options) {
6060
RCLCPP_INFO_STREAM(node_->get_logger(),
6161
"Started in 3D Lidar mode with topic: " << lidar_topic_);
6262
pointcloud_sub_ = node_->create_subscription<sensor_msgs::msg::PointCloud2>(
63-
lidar_topic_, rclcpp::SystemDefaultsQoS(),
63+
lidar_topic_, rclcpp::SensorDataQoS(),
6464
[&](const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg) {
6565
odometry_server_->RegisterFrame(msg);
6666
});

0 commit comments

Comments
 (0)