|
48 | 48 | #include "nav2_util/raytrace_line_2d.hpp" |
49 | 49 | #include "nav2_costmap_2d/costmap_math.hpp" |
50 | 50 | #include "nav2_ros_common/node_utils.hpp" |
| 51 | +#include "nav2_ros_common/interface_factories.hpp" |
51 | 52 | #include "rclcpp/version.h" |
52 | 53 |
|
53 | 54 | PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::ObstacleLayer, nav2_costmap_2d::Layer) |
@@ -95,6 +96,8 @@ void ObstacleLayer::onInitialize() |
95 | 96 | throw std::runtime_error{"Failed to lock node"}; |
96 | 97 | } |
97 | 98 |
|
| 99 | + allow_parameter_qos_overrides_ = nav2::declare_or_get_parameter(node, |
| 100 | + "allow_parameter_qos_overrides", true); |
98 | 101 | node->get_parameter(name_ + "." + "enabled", enabled_); |
99 | 102 | node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); |
100 | 103 | node->get_parameter(name_ + "." + "min_obstacle_height", min_obstacle_height_); |
@@ -133,9 +136,6 @@ void ObstacleLayer::onInitialize() |
133 | 136 |
|
134 | 137 | global_frame_ = layered_costmap_->getGlobalFrameID(); |
135 | 138 |
|
136 | | - auto sub_opt = rclcpp::SubscriptionOptions(); |
137 | | - sub_opt.callback_group = callback_group_; |
138 | | - |
139 | 139 | // now we need to split the topics based on whitespace which we can use a stringstream for |
140 | 140 | std::stringstream ss(topics_string); |
141 | 141 |
|
@@ -235,6 +235,9 @@ void ObstacleLayer::onInitialize() |
235 | 235 |
|
236 | 236 | // create a callback for the topic |
237 | 237 | if (data_type == "LaserScan") { |
| 238 | + auto sub_opt = nav2::interfaces::createSubscriptionOptions( |
| 239 | + topic, allow_parameter_qos_overrides_, callback_group_); |
| 240 | + |
238 | 241 | // For Kilted and Older Support from Message Filters API change |
239 | 242 | #if RCLCPP_VERSION_GTE(29, 6, 0) |
240 | 243 | std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> sub; |
@@ -289,6 +292,9 @@ void ObstacleLayer::onInitialize() |
289 | 292 | tf_filter_tolerance)); |
290 | 293 |
|
291 | 294 | } else { |
| 295 | + auto sub_opt = nav2::interfaces::createSubscriptionOptions( |
| 296 | + topic, allow_parameter_qos_overrides_, callback_group_); |
| 297 | + |
292 | 298 | // For Rolling and Newer Support from PointCloudTransport API change |
293 | 299 | #if RCLCPP_VERSION_GTE(30, 0, 0) |
294 | 300 | std::shared_ptr<point_cloud_transport::SubscriberFilter> sub; |
|
0 commit comments