Skip to content

Commit 4214d00

Browse files
committed
feat(perception): add pipeline_latency publishers
Signed-off-by: kminoda <koji.minoda@tier4.jp>
1 parent f0b8555 commit 4214d00

File tree

8 files changed

+52
-0
lines changed

8 files changed

+52
-0
lines changed

perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include <rclcpp/rclcpp.hpp>
2121
#include <tier4_autoware_utils/geometry/geometry.hpp>
22+
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
2223

2324
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
2425
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
@@ -48,6 +49,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
4849
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr object_pub_;
4950
rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr map_sub_;
5051
rclcpp::Subscription<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr object_sub_;
52+
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_{nullptr};
5153

5254
lanelet::LaneletMapPtr lanelet_map_ptr_;
5355
lanelet::ConstLanelets road_lanelets_;

perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include "detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp"
2121

2222
#include <rclcpp/rclcpp.hpp>
23+
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
2324

2425
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
2526
#include <sensor_msgs/msg/point_cloud2.hpp>
@@ -133,6 +134,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
133134
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr objects_pub_;
134135
message_filters::Subscriber<autoware_auto_perception_msgs::msg::DetectedObjects> objects_sub_;
135136
message_filters::Subscriber<sensor_msgs::msg::PointCloud2> obstacle_pointcloud_sub_;
137+
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_{nullptr};
136138
tf2_ros::Buffer tf_buffer_;
137139
tf2_ros::TransformListener tf_listener_;
138140

perception/detected_object_validation/src/object_lanelet_filter.cpp

+12
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,9 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod
5252
"input/object", rclcpp::QoS{1}, std::bind(&ObjectLaneletFilterNode::objectCallback, this, _1));
5353
object_pub_ = this->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
5454
"output/object", rclcpp::QoS{1});
55+
56+
debug_publisher_ =
57+
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "object_lanelet_filter");
5558
}
5659

5760
void ObjectLaneletFilterNode::mapCallback(
@@ -116,6 +119,15 @@ void ObjectLaneletFilterNode::objectCallback(
116119
++index;
117120
}
118121
object_pub_->publish(output_object_msg);
122+
123+
// Publish debug info
124+
const double pipeline_latency =
125+
std::chrono::duration<double, std::milli>(
126+
std::chrono::nanoseconds(
127+
(this->get_clock()->now() - output_object_msg.header.stamp).nanoseconds()))
128+
.count();
129+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
130+
"debug/pipeline_latency_ms", pipeline_latency);
119131
}
120132

121133
geometry_msgs::msg::Polygon ObjectLaneletFilterNode::setFootprint(

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -304,6 +304,8 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator(
304304

305305
objects_pub_ = create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
306306
"~/output/objects", rclcpp::QoS{1});
307+
debug_publisher_ = std::make_unique<tier4_autoware_utils::DebugPublisher>(
308+
this, "obstacle_pointcloud_based_validator");
307309

308310
const bool enable_debugger = declare_parameter<bool>("enable_debugger", false);
309311
if (enable_debugger) debugger_ = std::make_shared<Debugger>(this);
@@ -350,6 +352,14 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
350352
debugger_->publishNeighborPointcloud(input_obstacle_pointcloud->header);
351353
debugger_->publishPointcloudWithinPolygon(input_obstacle_pointcloud->header);
352354
}
355+
356+
// Publish processing time info
357+
const double pipeline_latency =
358+
std::chrono::duration<double, std::milli>(
359+
std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds()))
360+
.count();
361+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
362+
"debug/pipeline_latency_ms", pipeline_latency);
353363
}
354364

355365
} // namespace obstacle_pointcloud_based_validator

perception/euclidean_cluster/src/euclidean_cluster_node.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -75,10 +75,16 @@ void EuclideanClusterNode::onPointCloud(
7575
if (debug_publisher_) {
7676
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
7777
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
78+
const double pipeline_latency_ms =
79+
std::chrono::duration<double, std::milli>(
80+
std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds()))
81+
.count();
7882
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
7983
"debug/cyclic_time_ms", cyclic_time_ms);
8084
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
8185
"debug/processing_time_ms", processing_time_ms);
86+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
87+
"debug/pipeline_latency_ms", pipeline_latency_ms);
8288
}
8389
}
8490

perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -87,10 +87,16 @@ void VoxelGridBasedEuclideanClusterNode::onPointCloud(
8787
if (debug_publisher_) {
8888
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
8989
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
90+
const double pipeline_latency_ms =
91+
std::chrono::duration<double, std::milli>(
92+
std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds()))
93+
.count();
9094
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
9195
"debug/cyclic_time_ms", cyclic_time_ms);
9296
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
9397
"debug/processing_time_ms", processing_time_ms);
98+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
99+
"debug/pipeline_latency_ms", pipeline_latency_ms);
94100
}
95101
}
96102

perception/image_projection_based_fusion/src/fusion_node.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -175,11 +175,18 @@ void FusionNode<Msg, Obj, Msg2D>::subCallback(const typename Msg::ConstSharedPtr
175175
// add processing time for debug
176176
if (debug_publisher_) {
177177
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
178+
const double pipeline_latency_ms =
179+
std::chrono::duration<double, std::milli>(
180+
std::chrono::nanoseconds(
181+
(this->get_clock()->now() - cached_msg_.second->header.stamp).nanoseconds()))
182+
.count();
178183
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
179184
"debug/cyclic_time_ms", cyclic_time_ms);
180185
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
181186
"debug/processing_time_ms",
182187
processing_time_ms + stop_watch_ptr_->toc("processing_time", true));
188+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
189+
"debug/pipeline_latency_ms", pipeline_latency_ms);
183190
processing_time_ms = 0;
184191
}
185192
}

perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -206,10 +206,17 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
206206
if (debug_publisher_ptr_ && stop_watch_ptr_) {
207207
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
208208
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
209+
const double pipeline_latency_ms =
210+
std::chrono::duration<double, std::milli>(
211+
std::chrono::nanoseconds(
212+
(this->get_clock()->now() - input_raw_msg->header.stamp).nanoseconds()))
213+
.count();
209214
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
210215
"debug/cyclic_time_ms", cyclic_time_ms);
211216
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
212217
"debug/processing_time_ms", processing_time_ms);
218+
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
219+
"debug/pipeline_latency_ms", processing_time_ms);
213220
}
214221
}
215222

0 commit comments

Comments
 (0)