Skip to content

Commit f1e4a9e

Browse files
authored
feat(pointcloud_preprocessor): runtime configurable output topic qos (autowarefoundation#6658)
* feat(pointcloud_preprocessor): runtime configurable output topic qos Signed-off-by: Grzegorz Głowacki <gglowacki@autonomous-systems.pl> * configurable qos in livox_tag_filter_node Signed-off-by: Grzegorz Głowacki <gglowacki@autonomous-systems.pl> * configurable qos in radar_scan_to_pointcloud2 Signed-off-by: Grzegorz Głowacki <gglowacki@autonomous-systems.pl> --------- Signed-off-by: Grzegorz Głowacki <gglowacki@autonomous-systems.pl>
1 parent ced8e37 commit f1e4a9e

File tree

11 files changed

+58
-23
lines changed

11 files changed

+58
-23
lines changed

sensing/livox/autoware_livox_tag_filter/src/livox_tag_filter_node.cpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -47,9 +47,13 @@ LivoxTagFilterNode::LivoxTagFilterNode(const rclcpp::NodeOptions & node_options)
4747
sub_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
4848
"input", rclcpp::SensorDataQoS(), std::bind(&LivoxTagFilterNode::onPointCloud, this, _1));
4949

50-
// Publisher
51-
pub_pointcloud_ =
52-
this->create_publisher<sensor_msgs::msg::PointCloud2>("output", rclcpp::SensorDataQoS());
50+
{
51+
// Publisher
52+
rclcpp::PublisherOptions pub_options;
53+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
54+
pub_pointcloud_ = this->create_publisher<sensor_msgs::msg::PointCloud2>(
55+
"output", rclcpp::SensorDataQoS(), pub_options);
56+
}
5357
}
5458

5559
void LivoxTagFilterNode::onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+7-2
Original file line numberDiff line numberDiff line change
@@ -141,8 +141,10 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
141141

142142
// Output Publishers
143143
{
144+
rclcpp::PublisherOptions pub_options;
145+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
144146
pub_output_ = this->create_publisher<PointCloud2>(
145-
"output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
147+
"output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options);
146148
}
147149

148150
// Subscribers
@@ -192,10 +194,13 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
192194

193195
// Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud
194196
if (publish_synchronized_pointcloud_) {
197+
rclcpp::PublisherOptions pub_options;
198+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
199+
195200
for (auto & topic : input_topics_) {
196201
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_);
197202
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
198-
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
203+
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options);
199204
transformed_raw_pc_publisher_map_.insert({topic, publisher});
200205
}
201206
}

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -97,8 +97,10 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent(
9797

9898
// Output Publishers
9999
{
100+
rclcpp::PublisherOptions pub_options;
101+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
100102
pub_output_ = this->create_publisher<PointCloud2>(
101-
"output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
103+
"output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options);
102104
}
103105

104106
// Subscribers

sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -87,8 +87,10 @@ CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & optio
8787

8888
// set additional publishers
8989
{
90-
crop_box_polygon_pub_ =
91-
this->create_publisher<geometry_msgs::msg::PolygonStamped>("~/crop_box_polygon", 10);
90+
rclcpp::PublisherOptions pub_options;
91+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
92+
crop_box_polygon_pub_ = this->create_publisher<geometry_msgs::msg::PolygonStamped>(
93+
"~/crop_box_polygon", 10, pub_options);
9294
}
9395

9496
// set parameter service callback

sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -40,10 +40,13 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt
4040
time_stamp_field_name_ = declare_parameter("time_stamp_field_name", "time_stamp");
4141
use_imu_ = declare_parameter("use_imu", true);
4242

43-
// Publisher
44-
undistorted_points_pub_ =
45-
this->create_publisher<PointCloud2>("~/output/pointcloud", rclcpp::SensorDataQoS());
46-
43+
{
44+
rclcpp::PublisherOptions pub_options;
45+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
46+
// Publisher
47+
undistorted_points_pub_ = this->create_publisher<PointCloud2>(
48+
"~/output/pointcloud", rclcpp::SensorDataQoS(), pub_options);
49+
}
4750
// Subscriber
4851
twist_sub_ = this->create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
4952
"~/input/twist", 10,

sensing/pointcloud_preprocessor/src/filter.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -89,8 +89,10 @@ pointcloud_preprocessor::Filter::Filter(
8989

9090
// Set publisher
9191
{
92+
rclcpp::PublisherOptions pub_options;
93+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
9294
pub_output_ = this->create_publisher<PointCloud2>(
93-
"output", rclcpp::SensorDataQoS().keep_last(max_queue_size_));
95+
"output", rclcpp::SensorDataQoS().keep_last(max_queue_size_), pub_options);
9496
}
9597

9698
subscribe(filter_name);

sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -72,9 +72,12 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent(
7272
image_transport::create_publisher(this, "dual_return_outlier_filter/debug/frequency_image");
7373
visibility_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
7474
"dual_return_outlier_filter/debug/visibility", rclcpp::SensorDataQoS());
75-
noise_cloud_pub_ = create_publisher<sensor_msgs::msg::PointCloud2>(
76-
"dual_return_outlier_filter/debug/pointcloud_noise", rclcpp::SensorDataQoS());
77-
75+
{
76+
rclcpp::PublisherOptions pub_options;
77+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
78+
noise_cloud_pub_ = create_publisher<sensor_msgs::msg::PointCloud2>(
79+
"dual_return_outlier_filter/debug/pointcloud_noise", rclcpp::SensorDataQoS(), pub_options);
80+
}
7881
using std::placeholders::_1;
7982
set_param_res_ = this->add_on_set_parameters_callback(
8083
std::bind(&DualReturnOutlierFilterComponent::paramCallback, this, _1));

sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

+6-2
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,12 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
3333
using autoware::universe_utils::StopWatch;
3434
stop_watch_ptr_ = std::make_unique<StopWatch<std::chrono::milliseconds>>();
3535
debug_publisher_ = std::make_unique<DebugPublisher>(this, "ring_outlier_filter");
36-
outlier_pointcloud_publisher_ =
37-
this->create_publisher<PointCloud2>("debug/ring_outlier_filter", 1);
36+
{
37+
rclcpp::PublisherOptions pub_options;
38+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
39+
outlier_pointcloud_publisher_ =
40+
this->create_publisher<PointCloud2>("debug/ring_outlier_filter", 1, pub_options);
41+
}
3842
visibility_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
3943
"ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS());
4044
stop_watch_ptr_->tic("cyclic_time");

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -160,10 +160,12 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
160160

161161
// Transformed Raw PointCloud2 Publisher
162162
{
163+
rclcpp::PublisherOptions pub_options;
164+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
163165
for (auto & topic : input_topics_) {
164166
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix);
165167
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
166-
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
168+
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options);
167169
transformed_raw_pc_publisher_map_.insert({topic, publisher});
168170
}
169171
}

sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,10 @@ Lanelet2MapFilterComponent::Lanelet2MapFilterComponent(const rclcpp::NodeOptions
4545

4646
// Set publisher
4747
{
48+
rclcpp::PublisherOptions pub_options;
49+
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
4850
filtered_pointcloud_pub_ =
49-
this->create_publisher<PointCloud2>("output", rclcpp::SensorDataQoS());
51+
this->create_publisher<PointCloud2>("output", rclcpp::SensorDataQoS(), pub_options);
5052
}
5153

5254
// Set subscriber

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)