Skip to content

Commit 496fb5e

Browse files
feat(image_projection_based_fusion): add timekeeper (#9632)
* add timekeeper Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> * chore: refactor time-keeper position Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: bring back a missing comment Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: remove redundant timekeepers Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> Co-authored-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 9ee2c5a commit 496fb5e

File tree

11 files changed

+103
-0
lines changed

11 files changed

+103
-0
lines changed

perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -12,3 +12,6 @@
1212
filter_scope_max_x: 100.0
1313
filter_scope_max_y: 100.0
1414
filter_scope_max_z: 100.0
15+
16+
# debug parameters
17+
publish_processing_time_detail: false

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <autoware/image_projection_based_fusion/debugger.hpp>
1919
#include <autoware/universe_utils/ros/debug_publisher.hpp>
2020
#include <autoware/universe_utils/system/stop_watch.hpp>
21+
#include <autoware/universe_utils/system/time_keeper.hpp>
2122
#include <rclcpp/rclcpp.hpp>
2223

2324
#include <autoware_perception_msgs/msg/detected_objects.hpp>
@@ -142,6 +143,11 @@ class FusionNode : public rclcpp::Node
142143
/** \brief processing time publisher. **/
143144
std::unique_ptr<autoware::universe_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
144145
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
146+
147+
// timekeeper
148+
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
149+
detailed_processing_time_publisher_;
150+
std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_;
145151
};
146152

147153
} // namespace autoware::image_projection_based_fusion

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ class RoiClusterFusionNode
5353
double fusion_distance_;
5454
double trust_object_distance_;
5555
std::string non_trust_object_iou_mode_{"iou_x"};
56+
5657
bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold);
5758
bool out_of_scope(const DetectedObjectWithFeature & obj) override;
5859
double cal_iou_by_mode(

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,10 @@
1919

2020
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
2121

22+
#include <memory>
2223
#include <string>
2324
#include <vector>
25+
2426
namespace autoware::image_projection_based_fusion
2527
{
2628
class RoiPointCloudFusionNode

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
2121
#include <image_transport/image_transport.hpp>
2222

23+
#include <memory>
2324
#include <string>
2425
#include <unordered_set>
2526
#include <utility>

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

+21
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ static double processing_time_ms = 0;
4242

4343
namespace autoware::image_projection_based_fusion
4444
{
45+
using autoware::universe_utils::ScopedTimeTrack;
4546

4647
template <class TargetMsg3D, class ObjType, class Msg2D>
4748
FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
@@ -130,6 +131,17 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
130131
debugger_ =
131132
std::make_shared<Debugger>(this, rois_number_, image_buffer_size, input_camera_topics_);
132133
}
134+
135+
// time keeper
136+
bool use_time_keeper = declare_parameter<bool>("publish_processing_time_detail");
137+
if (use_time_keeper) {
138+
detailed_processing_time_publisher_ =
139+
this->create_publisher<autoware::universe_utils::ProcessingTimeDetail>(
140+
"~/debug/processing_time_detail_ms", 1);
141+
auto time_keeper = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_);
142+
time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(time_keeper);
143+
}
144+
133145
point_project_to_unrectified_image_ =
134146
declare_parameter<bool>("point_project_to_unrectified_image");
135147

@@ -170,6 +182,9 @@ template <class TargetMsg3D, class Obj, class Msg2D>
170182
void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
171183
const typename TargetMsg3D::ConstSharedPtr input_msg)
172184
{
185+
std::unique_ptr<ScopedTimeTrack> st_ptr;
186+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
187+
173188
if (cached_msg_.second != nullptr) {
174189
stop_watch_ptr_->toc("processing_time", true);
175190
timer_->cancel();
@@ -306,6 +321,9 @@ template <class TargetMsg3D, class Obj, class Msg2D>
306321
void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
307322
const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i)
308323
{
324+
std::unique_ptr<ScopedTimeTrack> st_ptr;
325+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
326+
309327
stop_watch_ptr_->toc("processing_time", true);
310328

311329
int64_t timestamp_nsec = (*input_roi_msg).header.stamp.sec * static_cast<int64_t>(1e9) +
@@ -378,6 +396,9 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::postprocess(TargetMsg3D & output_msg
378396
template <class TargetMsg3D, class Obj, class Msg2D>
379397
void FusionNode<TargetMsg3D, Obj, Msg2D>::timer_callback()
380398
{
399+
std::unique_ptr<ScopedTimeTrack> st_ptr;
400+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
401+
381402
using std::chrono_literals::operator""ms;
382403
timer_->cancel();
383404
if (mutex_cached_msgs_.try_lock()) {

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

+15
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <autoware/lidar_centerpoint/utils.hpp>
2525
#include <autoware/universe_utils/geometry/geometry.hpp>
2626
#include <autoware/universe_utils/math/constants.hpp>
27+
#include <autoware/universe_utils/system/time_keeper.hpp>
2728
#include <pcl_ros/transforms.hpp>
2829

2930
#include <omp.h>
@@ -35,6 +36,7 @@
3536

3637
namespace
3738
{
39+
using autoware::universe_utils::ScopedTimeTrack;
3840

3941
Eigen::Affine3f _transformToEigen(const geometry_msgs::msg::Transform & t)
4042
{
@@ -202,6 +204,9 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
202204

203205
void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg)
204206
{
207+
std::unique_ptr<ScopedTimeTrack> st_ptr;
208+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
209+
205210
if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) {
206211
RCLCPP_WARN_STREAM_THROTTLE(
207212
this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!");
@@ -273,6 +278,9 @@ void PointPaintingFusionNode::fuseOnSingleImage(
273278

274279
if (!checkCameraInfo(camera_info)) return;
275280

281+
std::unique_ptr<ScopedTimeTrack> st_ptr;
282+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
283+
276284
std::vector<sensor_msgs::msg::RegionOfInterest> debug_image_rois;
277285
std::vector<Eigen::Vector2d> debug_image_points;
278286

@@ -372,6 +380,10 @@ dc | dc dc dc dc ||zc|
372380
}
373381

374382
if (debugger_) {
383+
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;
384+
if (time_keeper_)
385+
inner_st_ptr = std::make_unique<ScopedTimeTrack>("publish debug message", *time_keeper_);
386+
375387
debugger_->image_rois_ = debug_image_rois;
376388
debugger_->obstacle_points_ = debug_image_points;
377389
debugger_->publishImage(image_id, input_roi_msg.header.stamp);
@@ -380,6 +392,9 @@ dc | dc dc dc dc ||zc|
380392

381393
void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg)
382394
{
395+
std::unique_ptr<ScopedTimeTrack> st_ptr;
396+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
397+
383398
const auto objects_sub_count =
384399
obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count();
385400
if (objects_sub_count < 1) {

perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,14 @@
1616

1717
#include <autoware/image_projection_based_fusion/utils/geometry.hpp>
1818
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
19+
#include <autoware/universe_utils/system/time_keeper.hpp>
1920

2021
#include <sensor_msgs/msg/point_cloud2.hpp>
2122
#include <sensor_msgs/point_cloud2_iterator.hpp>
2223

2324
#include <algorithm>
2425
#include <map>
26+
#include <memory>
2527
#include <string>
2628
#include <utility>
2729
#include <vector>
@@ -36,6 +38,7 @@
3638

3739
namespace autoware::image_projection_based_fusion
3840
{
41+
using autoware::universe_utils::ScopedTimeTrack;
3942

4043
RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options)
4144
: FusionNode<DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>(
@@ -55,6 +58,9 @@ RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options)
5558

5659
void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluster_msg)
5760
{
61+
std::unique_ptr<ScopedTimeTrack> st_ptr;
62+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
63+
5864
// reset cluster semantic type
5965
if (!use_cluster_semantic_type_) {
6066
for (auto & feature_object : output_cluster_msg.feature_objects) {
@@ -67,6 +73,9 @@ void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluste
6773

6874
void RoiClusterFusionNode::postprocess(DetectedObjectsWithFeature & output_cluster_msg)
6975
{
76+
std::unique_ptr<ScopedTimeTrack> st_ptr;
77+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
78+
7079
if (!remove_unknown_) {
7180
return;
7281
}
@@ -91,6 +100,9 @@ void RoiClusterFusionNode::fuseOnSingleImage(
91100
{
92101
if (!checkCameraInfo(camera_info)) return;
93102

103+
std::unique_ptr<ScopedTimeTrack> st_ptr;
104+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
105+
94106
image_geometry::PinholeCameraModel pinhole_camera_model;
95107
pinhole_camera_model.fromCameraInfo(camera_info);
96108

@@ -110,6 +122,7 @@ void RoiClusterFusionNode::fuseOnSingleImage(
110122
}
111123

112124
std::map<std::size_t, RegionOfInterest> m_cluster_roi;
125+
113126
for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) {
114127
if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) {
115128
continue;

perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp

+15
Original file line numberDiff line numberDiff line change
@@ -18,14 +18,17 @@
1818

1919
#include <autoware/image_projection_based_fusion/utils/geometry.hpp>
2020
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
21+
#include <autoware/universe_utils/system/time_keeper.hpp>
2122

2223
#include <algorithm>
2324
#include <map>
25+
#include <memory>
2426
#include <utility>
2527
#include <vector>
2628

2729
namespace autoware::image_projection_based_fusion
2830
{
31+
using autoware::universe_utils::ScopedTimeTrack;
2932

3033
RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options)
3134
: FusionNode<DetectedObjects, DetectedObject, DetectedObjectsWithFeature>(
@@ -49,6 +52,9 @@ RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptio
4952

5053
void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg)
5154
{
55+
std::unique_ptr<ScopedTimeTrack> st_ptr;
56+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
57+
5258
std::vector<bool> passthrough_object_flags, fused_object_flags, ignored_object_flags;
5359
passthrough_object_flags.resize(output_msg.objects.size());
5460
fused_object_flags.resize(output_msg.objects.size());
@@ -81,6 +87,9 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage(
8187
const sensor_msgs::msg::CameraInfo & camera_info,
8288
DetectedObjects & output_object_msg __attribute__((unused)))
8389
{
90+
std::unique_ptr<ScopedTimeTrack> st_ptr;
91+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
92+
8493
if (!checkCameraInfo(camera_info)) return;
8594

8695
Eigen::Affine3d object2camera_affine;
@@ -117,6 +126,9 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
117126
const Eigen::Affine3d & object2camera_affine,
118127
const image_geometry::PinholeCameraModel & pinhole_camera_model)
119128
{
129+
std::unique_ptr<ScopedTimeTrack> st_ptr;
130+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
131+
120132
std::map<std::size_t, DetectedObjectWithFeature> object_roi_map;
121133
int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast<int64_t>(1e9) +
122134
input_object_msg.header.stamp.nanosec;
@@ -202,6 +214,9 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage(
202214
const std::vector<DetectedObjectWithFeature> & image_rois,
203215
const std::map<std::size_t, DetectedObjectWithFeature> & object_roi_map)
204216
{
217+
std::unique_ptr<ScopedTimeTrack> st_ptr;
218+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
219+
205220
int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast<int64_t>(1e9) +
206221
input_object_msg.header.stamp.nanosec;
207222
if (fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) {

perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,9 @@
1717
#include "autoware/image_projection_based_fusion/utils/geometry.hpp"
1818
#include "autoware/image_projection_based_fusion/utils/utils.hpp"
1919

20+
#include <autoware/universe_utils/system/time_keeper.hpp>
21+
22+
#include <memory>
2023
#include <vector>
2124

2225
#ifdef ROS_DISTRO_GALACTIC
@@ -31,6 +34,8 @@
3134

3235
namespace autoware::image_projection_based_fusion
3336
{
37+
using autoware::universe_utils::ScopedTimeTrack;
38+
3439
RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options)
3540
: FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>(
3641
"roi_pointcloud_fusion", options)
@@ -47,12 +52,18 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt
4752
void RoiPointCloudFusionNode::preprocess(
4853
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg)
4954
{
55+
std::unique_ptr<ScopedTimeTrack> st_ptr;
56+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
57+
5058
return;
5159
}
5260

5361
void RoiPointCloudFusionNode::postprocess(
5462
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg)
5563
{
64+
std::unique_ptr<ScopedTimeTrack> st_ptr;
65+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
66+
5667
const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() +
5768
pub_objects_ptr_->get_intra_process_subscription_count();
5869
if (objects_sub_count < 1) {
@@ -81,6 +92,9 @@ void RoiPointCloudFusionNode::fuseOnSingleImage(
8192
const sensor_msgs::msg::CameraInfo & camera_info,
8293
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & output_pointcloud_msg)
8394
{
95+
std::unique_ptr<ScopedTimeTrack> st_ptr;
96+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
97+
8498
if (input_pointcloud_msg.data.empty()) {
8599
return;
86100
}

perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+12
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "autoware/image_projection_based_fusion/utils/geometry.hpp"
1818
#include "autoware/image_projection_based_fusion/utils/utils.hpp"
1919

20+
#include <autoware/universe_utils/system/time_keeper.hpp>
2021
#include <perception_utils/run_length_encoder.hpp>
2122

2223
#include <memory>
@@ -32,6 +33,8 @@
3233

3334
namespace autoware::image_projection_based_fusion
3435
{
36+
using autoware::universe_utils::ScopedTimeTrack;
37+
3538
SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options)
3639
: FusionNode<PointCloud2, PointCloud2, Image>("segmentation_pointcloud_fusion", options)
3740
{
@@ -49,11 +52,17 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
4952

5053
void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
5154
{
55+
std::unique_ptr<ScopedTimeTrack> st_ptr;
56+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
57+
5258
return;
5359
}
5460

5561
void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg)
5662
{
63+
std::unique_ptr<ScopedTimeTrack> st_ptr;
64+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
65+
5766
auto original_cloud = std::make_shared<PointCloud2>(pointcloud_msg);
5867

5968
int point_step = original_cloud->point_step;
@@ -82,6 +91,9 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
8291
[[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info,
8392
__attribute__((unused)) PointCloud2 & output_cloud)
8493
{
94+
std::unique_ptr<ScopedTimeTrack> st_ptr;
95+
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
96+
8597
if (input_pointcloud_msg.data.empty()) {
8698
return;
8799
}

0 commit comments

Comments
 (0)