diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index c7f2bb5bdc60d..084e939ff40a9 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -87,7 +87,7 @@ RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOpt // Subscriber sub_radar_ = create_subscription( - "~/input/radar_objects", rclcpp::QoS{1}, + "~/input/radar_objects", rclcpp::QoS{1}.best_effort(), std::bind(&RadarTracksMsgsConverterNode::onRadarTracks, this, _1)); sub_odometry_ = create_subscription( "~/input/odometry", rclcpp::QoS{1}, diff --git a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp index 5bd143a42eced..82a0a21ff6fdc 100644 --- a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp +++ b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp @@ -56,7 +56,7 @@ RadarTrackCrossingNoiseFilterNode::RadarTrackCrossingNoiseFilterNode( // Subscriber sub_tracks_ = create_subscription( - "~/input/tracks", rclcpp::QoS{1}, + "~/input/tracks", rclcpp::QoS{1}.best_effort(), std::bind(&RadarTrackCrossingNoiseFilterNode::onTracks, this, std::placeholders::_1)); // Publisher