Skip to content

Commit f97675f

Browse files
committed
Bugfix: cannot receive scan topic with best-effort qos.
This implementation uses message filter to sub topic. But message filter default only passes topic with reliable qos. I modified the qos setting in message filter to pass both reliable and best-effort topic.
1 parent b0be675 commit f97675f

1 file changed

Lines changed: 1 addition & 1 deletion

File tree

slam_gmapping/src/slam_gmapping.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ void SlamGmapping::startLiveSlam() {
9696
sst_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map");
9797
sstm_ = this->create_publisher<nav_msgs::msg::MapMetaData>("map_metadata");
9898
scan_filter_sub_ = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>
99-
(node_, "scan");
99+
(node_, "scan", rmw_qos_profile_sensor_data);
100100
scan_filter_ = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>
101101
(*scan_filter_sub_, *buffer_, odom_frame_, 10, node_);
102102
scan_filter_->registerCallback(std::bind(&SlamGmapping::laserCallback, this, std::placeholders::_1));

0 commit comments

Comments
 (0)