Skip to content

Commit

Permalink
Merge pull request #12 from lge-ros2/foxy-devel
Browse files Browse the repository at this point in the history
Backport 2518 (ros-navigation#2677)
  • Loading branch information
hyunseok-yang authored Dec 15, 2021
2 parents 9f0f56a + 8a8b4d2 commit ac05557
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
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

0 comments on commit ac05557

Please sign in to comment.