Skip to content

Commit

Permalink
Bugfix: cannot receive scan topic with best-effort qos.
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
skylerpan committed Mar 1, 2020
1 parent b0be675 commit f97675f
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion slam_gmapping/src/slam_gmapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void SlamGmapping::startLiveSlam() {
sst_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map");
sstm_ = this->create_publisher<nav_msgs::msg::MapMetaData>("map_metadata");
scan_filter_sub_ = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>
(node_, "scan");
(node_, "scan", rmw_qos_profile_sensor_data);
scan_filter_ = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>
(*scan_filter_sub_, *buffer_, odom_frame_, 10, node_);
scan_filter_->registerCallback(std::bind(&SlamGmapping::laserCallback, this, std::placeholders::_1));
Expand Down

0 comments on commit f97675f

Please sign in to comment.