Skip to content

Commit 1f6b87d

Browse files
brkay54autoware
authored and
autoware
committed
feat(pointcloud_preprocessor): add pipeline latency time debug information for pointcloud pipeline (autowarefoundation#6056)
1 parent 8b1c891 commit 1f6b87d

File tree

6 files changed

+80
-2
lines changed

6 files changed

+80
-2
lines changed

sensing/pointcloud_preprocessor/README.md

+39-1
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,45 @@ Detail description of each filter's algorithm is in the following links.
5656

5757
## Assumptions / Known limits
5858

59-
`pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because of [this issue](https://github.com/ros-perception/perception_pcl/issues/9).
59+
`pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because
60+
of [this issue](https://github.com/ros-perception/perception_pcl/issues/9).
61+
62+
## Measuring the performance
63+
64+
In Autoware, point cloud data from each LiDAR sensor undergoes preprocessing in the sensing pipeline before being input
65+
into the perception pipeline. The preprocessing stages are illustrated in the diagram below:
66+
67+
![pointcloud_preprocess_pipeline.drawio.png](docs%2Fimage%2Fpointcloud_preprocess_pipeline.drawio.png)
68+
69+
Each stage in the pipeline incurs a processing delay. Mostly, we've used `ros2 topic delay /topic_name` to measure
70+
the time between the message header and the current time. This approach works well for small-sized messages. However,
71+
when dealing with large point cloud messages, this method introduces an additional delay. This is primarily because
72+
accessing these large point cloud messages externally impacts the pipeline's performance.
73+
74+
Our sensing/perception nodes are designed to run within composable node containers, leveraging intra-process
75+
communication. External subscriptions to these messages (like using ros2 topic delay or rviz2) impose extra delays and
76+
can even slow down the pipeline by subscribing externally. Therefore, these measurements will not be accurate.
77+
78+
To mitigate this issue, we've adopted a method where each node in the pipeline reports its pipeline latency time.
79+
This approach ensures the integrity of intra-process communication and provides a more accurate measure of delays in the
80+
pipeline.
81+
82+
### Benchmarking The Pipeline
83+
84+
The nodes within the pipeline report the pipeline latency time, indicating the duration from the sensor driver's pointcloud
85+
output to the node's output. This data is crucial for assessing the pipeline's health and efficiency.
86+
87+
When running Autoware, you can monitor the pipeline latency times for each node in the pipeline by subscribing to the
88+
following ROS 2 topics:
89+
90+
- `/sensing/lidar/LidarX/crop_box_filter_self/debug/pipeline_latency_ms`
91+
- `/sensing/lidar/LidarX/crop_box_filter_mirror/debug/pipeline_latency_ms`
92+
- `/sensing/lidar/LidarX/distortion_corrector/debug/pipeline_latency_ms`
93+
- `/sensing/lidar/LidarX/ring_outlier_filter/debug/pipeline_latency_ms`
94+
- `/sensing/lidar/concatenate_data_synchronizer/debug/sensing/lidar/LidarX/pointcloud/pipeline_latency_ms`
95+
96+
These topics provide the pipeline latency times, giving insights into the delays at various stages of the pipeline
97+
from the sensor output of LidarX to each subsequent node.
6098

6199
## (Optional) Error detection and handling
62100

Loading

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -427,6 +427,20 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
427427
const auto & transformed_raw_points =
428428
PointCloudConcatenateDataSynchronizerComponent::combineClouds(concat_cloud_ptr);
429429

430+
for (const auto & e : cloud_stdmap_) {
431+
if (e.second != nullptr) {
432+
if (debug_publisher_) {
433+
const auto pipeline_latency_ms =
434+
std::chrono::duration<double, std::milli>(
435+
std::chrono::nanoseconds(
436+
(this->get_clock()->now() - e.second->header.stamp).nanoseconds()))
437+
.count();
438+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
439+
"debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms);
440+
}
441+
}
442+
}
443+
430444
// publish concatenated pointcloud
431445
if (concat_cloud_ptr) {
432446
auto output = std::make_unique<sensor_msgs::msg::PointCloud2>(*concat_cloud_ptr);

sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp

+9-1
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & optio
6565
using tier4_autoware_utils::DebugPublisher;
6666
using tier4_autoware_utils::StopWatch;
6767
stop_watch_ptr_ = std::make_unique<StopWatch<std::chrono::milliseconds>>();
68-
debug_publisher_ = std::make_unique<DebugPublisher>(this, "crop_box_filter");
68+
debug_publisher_ = std::make_unique<DebugPublisher>(this, this->get_name());
6969
stop_watch_ptr_->tic("cyclic_time");
7070
stop_watch_ptr_->tic("processing_time");
7171
}
@@ -195,6 +195,14 @@ void CropBoxFilterComponent::faster_filter(
195195
"debug/cyclic_time_ms", cyclic_time_ms);
196196
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
197197
"debug/processing_time_ms", processing_time_ms);
198+
199+
auto pipeline_latency_ms =
200+
std::chrono::duration<double, std::milli>(
201+
std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds()))
202+
.count();
203+
204+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
205+
"debug/pipeline_latency_ms", pipeline_latency_ms);
198206
}
199207
}
200208

sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -128,6 +128,16 @@ void DistortionCorrectorComponent::onPointCloud(PointCloud2::UniquePtr points_ms
128128

129129
undistortPointCloud(tf2_base_link_to_sensor, *points_msg);
130130

131+
if (debug_publisher_) {
132+
auto pipeline_latency_ms =
133+
std::chrono::duration<double, std::milli>(
134+
std::chrono::nanoseconds(
135+
(this->get_clock()->now() - points_msg->header.stamp).nanoseconds()))
136+
.count();
137+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
138+
"debug/pipeline_latency_ms", pipeline_latency_ms);
139+
}
140+
131141
undistorted_points_pub_->publish(std::move(points_msg));
132142

133143
// add processing time for debug

sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

+8
Original file line numberDiff line numberDiff line change
@@ -346,6 +346,14 @@ void RingOutlierFilterComponent::faster_filter(
346346
"debug/cyclic_time_ms", cyclic_time_ms);
347347
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
348348
"debug/processing_time_ms", processing_time_ms);
349+
350+
auto pipeline_latency_ms =
351+
std::chrono::duration<double, std::milli>(
352+
std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds()))
353+
.count();
354+
355+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
356+
"debug/pipeline_latency_ms", pipeline_latency_ms);
349357
}
350358
}
351359

0 commit comments

Comments
 (0)