Skip to content

Commit 39715d2

Browse files
authored
Merge pull request #1 from skylerpan/dashing-devel
Update master branch.
2 parents f0ed9bc + 465b184 commit 39715d2

2 files changed

Lines changed: 2 additions & 2 deletions

File tree

slam_gmapping/launch/slam_gmapping.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
def generate_launch_description():
66
param_substitutions = {
77
'base_frame': 'base_link',
8-
'odom_frame': 'base_odom',
8+
'odom_frame': 'odom',
99
'map_frame': 'map',
1010
'map_update_interval': '3.0',
1111
'maxUrange': '10.0',

slam_gmapping/src/slam_gmapping.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,7 @@ void SlamGmapping::startLiveSlam() {
149149
sst_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map");
150150
sstm_ = this->create_publisher<nav_msgs::msg::MapMetaData>("map_metadata");
151151
scan_filter_sub_ = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>
152-
(node_, "scan");
152+
(node_, "scan", rmw_qos_profile_sensor_data);
153153
scan_filter_ = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>
154154
(*scan_filter_sub_, *buffer_, odom_frame_, 10, node_);
155155
scan_filter_->registerCallback(std::bind(&SlamGmapping::laserCallback, this, std::placeholders::_1));

0 commit comments

Comments
 (0)