Skip to content

Commit 8a8b4d2

Browse files
mdtoomMatthijs den Toom
andauthored
Backport 2518 (#2677)
Co-authored-by: Matthijs den Toom <[email protected]>
1 parent 1d0e56a commit 8a8b4d2

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

nav2_amcl/src/amcl_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1246,7 +1246,7 @@ AmclNode::initMessageFilters()
12461246
rclcpp_node_.get(), scan_topic_, rmw_qos_profile_sensor_data);
12471247

12481248
laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
1249-
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10, rclcpp_node_);
1249+
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10, rclcpp_node_, transform_tolerance_);
12501250

12511251
laser_scan_connection_ = laser_scan_filter_->registerCallback(
12521252
std::bind(

nav2_costmap_2d/plugins/obstacle_layer.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,7 @@ void ObstacleLayer::onInitialize()
205205

206206
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> filter(
207207
new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
208-
*sub, *tf_, global_frame_, 50, rclcpp_node_));
208+
*sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
209209

210210
if (inf_is_valid) {
211211
filter->registerCallback(
@@ -239,7 +239,7 @@ void ObstacleLayer::onInitialize()
239239

240240
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>> filter(
241241
new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
242-
*sub, *tf_, global_frame_, 50, rclcpp_node_));
242+
*sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
243243

244244
filter->registerCallback(
245245
std::bind(

0 commit comments

Comments
 (0)