Skip to content

Commit

Permalink
feat(perception): add pipeline_latency_ms publisher (autowarefoundati…
Browse files Browse the repository at this point in the history
…on#6181)

Signed-off-by: kminoda <[email protected]>
  • Loading branch information
kminoda authored and StepTurtle committed Feb 27, 2024
1 parent e897ed5 commit 34e3316
Show file tree
Hide file tree
Showing 9 changed files with 62 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
Expand All @@ -27,6 +28,7 @@
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <string>

namespace object_lanelet_filter
Expand All @@ -48,6 +50,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr object_pub_;
rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr map_sub_;
rclcpp::Subscription<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr object_sub_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_{nullptr};

lanelet::LaneletMapPtr lanelet_map_ptr_;
lanelet::ConstLanelets road_lanelets_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp"

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod
"input/object", rclcpp::QoS{1}, std::bind(&ObjectLaneletFilterNode::objectCallback, this, _1));
object_pub_ = this->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"output/object", rclcpp::QoS{1});

debug_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "object_lanelet_filter");
}

void ObjectLaneletFilterNode::mapCallback(
Expand Down Expand Up @@ -116,6 +119,15 @@ void ObjectLaneletFilterNode::objectCallback(
++index;
}
object_pub_->publish(output_object_msg);

// Publish debug info
const double pipeline_latency =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - output_object_msg.header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency);
}

geometry_msgs::msg::Polygon ObjectLaneletFilterNode::setFootprint(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -304,6 +304,8 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator(

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

const bool enable_debugger = declare_parameter<bool>("enable_debugger", false);
if (enable_debugger) debugger_ = std::make_shared<Debugger>(this);
Expand Down Expand Up @@ -350,6 +352,14 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
debugger_->publishNeighborPointcloud(input_obstacle_pointcloud->header);
debugger_->publishPointcloudWithinPolygon(input_obstacle_pointcloud->header);
}

// Publish processing time info
const double pipeline_latency =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency);
}

} // namespace obstacle_pointcloud_based_validator
Expand Down
11 changes: 7 additions & 4 deletions perception/euclidean_cluster/src/euclidean_cluster_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,21 +64,24 @@ void EuclideanClusterNode::onPointCloud(
cluster_pub_->publish(output);

// build debug msg
if (debug_pub_->get_subscription_count() < 1) {
return;
}
{
if (debug_pub_->get_subscription_count() >= 1) {
sensor_msgs::msg::PointCloud2 debug;
convertObjectMsg2SensorMsg(output, debug);
debug_pub_->publish(debug);
}
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,21 +76,24 @@ void VoxelGridBasedEuclideanClusterNode::onPointCloud(
cluster_pub_->publish(output);

// build debug msg
if (debug_pub_->get_subscription_count() < 1) {
return;
}
{
if (debug_pub_->get_subscription_count() >= 1) {
sensor_msgs::msg::PointCloud2 debug;
convertObjectMsg2SensorMsg(output, debug);
debug_pub_->publish(debug);
}
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}

Expand Down
7 changes: 7 additions & 0 deletions perception/image_projection_based_fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,11 +173,18 @@ void FusionNode<Msg, Obj, Msg2D>::subCallback(const typename Msg::ConstSharedPtr
// add processing time for debug
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - cached_msg_.second->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms",
processing_time_ms + stop_watch_ptr_->toc("processing_time", true));
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
processing_time_ms = 0;
}
}
Expand Down
7 changes: 7 additions & 0 deletions perception/lidar_centerpoint/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,10 +169,17 @@ void LidarCenterPointNode::pointCloudCallback(
if (debug_publisher_ptr_ && stop_watch_ptr_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - output_msg.header.stamp).nanoseconds()))
.count();
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -206,10 +206,17 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
if (debug_publisher_ptr_ && stop_watch_ptr_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - input_raw_msg->header.stamp).nanoseconds()))
.count();
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}

Expand Down

0 comments on commit 34e3316

Please sign in to comment.