Skip to content

Commit 9cf3e75

Browse files
committed
configurable qos in radar_scan_to_pointcloud2
Signed-off-by: Grzegorz Głowacki <gglowacki@autonomous-systems.pl>
1 parent 1925228 commit 9cf3e75

File tree

1 file changed

+9
-3
lines changed

1 file changed

+9
-3
lines changed

Diff for: sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp

+9-3
Original file line numberDiff line numberDiff line change
@@ -111,9 +111,15 @@ RadarScanToPointcloud2Node::RadarScanToPointcloud2Node(const rclcpp::NodeOptions
111111
sub_radar_ = create_subscription<RadarScan>(
112112
"~/input/radar", rclcpp::QoS{1}, std::bind(&RadarScanToPointcloud2Node::onData, this, _1));
113113

114-
// Publisher
115-
pub_amplitude_pointcloud_ = create_publisher<PointCloud2>("~/output/amplitude_pointcloud", 1);
116-
pub_doppler_pointcloud_ = create_publisher<PointCloud2>("~/output/doppler_pointcloud", 1);
114+
{
115+
rclcpp::PublisherOptions pub_options;
116+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
117+
// Publisher
118+
pub_amplitude_pointcloud_ =
119+
create_publisher<PointCloud2>("~/output/amplitude_pointcloud", 1, pub_options);
120+
pub_doppler_pointcloud_ =
121+
create_publisher<PointCloud2>("~/output/doppler_pointcloud", 1, pub_options);
122+
}
117123
}
118124

119125
rcl_interfaces::msg::SetParametersResult RadarScanToPointcloud2Node::onSetParam(

0 commit comments

Comments
 (0)