diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 37da4a8253..3a4e0492d0 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -1246,7 +1246,7 @@ AmclNode::initMessageFilters() rclcpp_node_.get(), scan_topic_, rmw_qos_profile_sensor_data); laser_scan_filter_ = std::make_unique>( - *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10, rclcpp_node_); + *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10, rclcpp_node_, transform_tolerance_); laser_scan_connection_ = laser_scan_filter_->registerCallback( std::bind( diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp index 7c91156357..a881f14f49 100644 --- a/nav2_costmap_2d/plugins/obstacle_layer.cpp +++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp @@ -205,7 +205,7 @@ void ObstacleLayer::onInitialize() std::shared_ptr> filter( new tf2_ros::MessageFilter( - *sub, *tf_, global_frame_, 50, rclcpp_node_)); + *sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance))); if (inf_is_valid) { filter->registerCallback( @@ -239,7 +239,7 @@ void ObstacleLayer::onInitialize() std::shared_ptr> filter( new tf2_ros::MessageFilter( - *sub, *tf_, global_frame_, 50, rclcpp_node_)); + *sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance))); filter->registerCallback( std::bind(