Skip to content

Commit 1592cac

Browse files
committed
feat: change radar tracks subscription qos to besteffort
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 5938bed commit 1592cac

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOpt
8888

8989
// Subscriber
9090
sub_radar_ = create_subscription<RadarTracks>(
91-
"~/input/radar_objects", rclcpp::QoS{1},
91+
"~/input/radar_objects", rclcpp::QoS{1}.best_effort(),
9292
std::bind(&RadarTracksMsgsConverterNode::onRadarTracks, this, _1));
9393
sub_odometry_ = create_subscription<Odometry>(
9494
"~/input/odometry", rclcpp::QoS{1},

sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ RadarTrackCrossingNoiseFilterNode::RadarTrackCrossingNoiseFilterNode(
5656

5757
// Subscriber
5858
sub_tracks_ = create_subscription<RadarTracks>(
59-
"~/input/tracks", rclcpp::QoS{1},
59+
"~/input/tracks", rclcpp::QoS{1}.best_effort(),
6060
std::bind(&RadarTrackCrossingNoiseFilterNode::onTracks, this, std::placeholders::_1));
6161

6262
// Publisher

0 commit comments

Comments
 (0)