Skip to content

Commit 5c5fc77

Browse files
doisygSteveMacenski
authored andcommitted
[ObstacleLayer] Use message_filter timeout (#2518)
* , tf2::durationFromSec(transform_tolerance) * use message_filter timeout in AMCL * also for sensor_msgs::msg::PointCloud2
1 parent 2acd470 commit 5c5fc77

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
@@ -1241,7 +1241,7 @@ AmclNode::initMessageFilters()
12411241
rclcpp_node_.get(), scan_topic_, rmw_qos_profile_sensor_data);
12421242

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

12461246
laser_scan_connection_ = laser_scan_filter_->registerCallback(
12471247
std::bind(

nav2_costmap_2d/plugins/obstacle_layer.cpp

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

219219
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> filter(
220220
new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
221-
*sub, *tf_, global_frame_, 50, rclcpp_node_));
221+
*sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
222222

223223
if (inf_is_valid) {
224224
filter->registerCallback(
@@ -252,7 +252,7 @@ void ObstacleLayer::onInitialize()
252252

253253
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>> filter(
254254
new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
255-
*sub, *tf_, global_frame_, 50, rclcpp_node_));
255+
*sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
256256

257257
filter->registerCallback(
258258
std::bind(

0 commit comments

Comments
 (0)