diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp index 6321305dd79..3ba1c97f08a 100644 --- a/nav2_costmap_2d/plugins/obstacle_layer.cpp +++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp @@ -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") {