Skip to content

Commit

Permalink
[nav2_costmap_2d] Fix obstacle_layer trying to use RELIABLE QoS
Browse files Browse the repository at this point in the history
Use QoS profile from rclcpp::SensorDataQoS() instead of rmw_qos_profile_t.
This solves an issue where the subscriber uses RELIABLE setting even when initialized from rmw_qos_profile_sensor_data.
In addition the Subscriber(..., rmw_qos_profile_t) constructor is deprecated in favor of Subscriber(..., rclcpp::QoS)
  • Loading branch information
adivardi committed Oct 9, 2024
1 parent dbd37aa commit 3ff8e0c
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,8 +225,7 @@ void ObstacleLayer::onInitialize()
source.c_str(), topic.c_str(),
global_frame_.c_str(), expected_update_rate, observation_keep_time);

rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
custom_qos_profile.depth = 50;
const auto custom_qos_profile = rclcpp::SensorDataQoS().keep_last(50);

// create a callback for the topic
if (data_type == "LaserScan") {
Expand Down

0 comments on commit 3ff8e0c

Please sign in to comment.