Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Backport 2518 (#2677) #12

Merged
merged 1 commit into from
Dec 15, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1246,7 +1246,7 @@ AmclNode::initMessageFilters()
rclcpp_node_.get(), scan_topic_, rmw_qos_profile_sensor_data);

laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*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(
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ void ObstacleLayer::onInitialize()

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

if (inf_is_valid) {
filter->registerCallback(
Expand Down Expand Up @@ -239,7 +239,7 @@ void ObstacleLayer::onInitialize()

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

filter->registerCallback(
std::bind(
Expand Down