Skip to content

Commit b307b3d

Browse files
authored
chore(radar_track_msgs_converter): change radar tracks subscription qos to besteffort (#6864)
feat: change radar tracks subscription qos to besteffort Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 4740914 commit b307b3d

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
@@ -87,7 +87,7 @@ RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOpt
8787

8888
// Subscriber
8989
sub_radar_ = create_subscription<RadarTracks>(
90-
"~/input/radar_objects", rclcpp::QoS{1},
90+
"~/input/radar_objects", rclcpp::QoS{1}.best_effort(),
9191
std::bind(&RadarTracksMsgsConverterNode::onRadarTracks, this, _1));
9292
sub_odometry_ = create_subscription<Odometry>(
9393
"~/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)