|
46 | 46 | #include "pluginlib/class_list_macros.hpp" |
47 | 47 | #include "sensor_msgs/point_cloud2_iterator.hpp" |
48 | 48 | #include "nav2_costmap_2d/costmap_math.hpp" |
| 49 | +#include "nav2_util/node_utils.hpp" |
49 | 50 | #include "rclcpp/version.h" |
50 | 51 |
|
51 | 52 | PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::ObstacleLayer, nav2_costmap_2d::Layer) |
@@ -100,6 +101,8 @@ void ObstacleLayer::onInitialize() |
100 | 101 | node->get_parameter("track_unknown_space", track_unknown_space); |
101 | 102 | node->get_parameter("transform_tolerance", transform_tolerance); |
102 | 103 | node->get_parameter(name_ + "." + "observation_sources", topics_string); |
| 104 | + double tf_filter_tolerance = nav2_util::declare_or_get_parameter(node, name_ + "." + |
| 105 | + "tf_filter_tolerance", 0.05); |
103 | 106 |
|
104 | 107 | int combination_method_param{}; |
105 | 108 | node->get_parameter(name_ + "." + "combination_method", combination_method_param); |
@@ -278,7 +281,8 @@ void ObstacleLayer::onInitialize() |
278 | 281 | observation_subscribers_.push_back(sub); |
279 | 282 |
|
280 | 283 | observation_notifiers_.push_back(filter); |
281 | | - observation_notifiers_.back()->setTolerance(rclcpp::Duration::from_seconds(0.05)); |
| 284 | + observation_notifiers_.back()->setTolerance(rclcpp::Duration::from_seconds( |
| 285 | + tf_filter_tolerance)); |
282 | 286 |
|
283 | 287 | } else { |
284 | 288 | // For Kilted and Older Support from Message Filters API change |
|
0 commit comments