Skip to content

Commit

Permalink
feat(image_projection_based_fusion): add timekeeper (autowarefoundati…
Browse files Browse the repository at this point in the history
…on#9632)

* add timekeeper

Signed-off-by: a-maumau <[email protected]>

* chore: refactor time-keeper position

Signed-off-by: Taekjin LEE <[email protected]>

* chore: bring back a missing comment

Signed-off-by: Taekjin LEE <[email protected]>

* chore: remove redundant timekeepers

Signed-off-by: Taekjin LEE <[email protected]>

---------

Signed-off-by: a-maumau <[email protected]>
Signed-off-by: Taekjin LEE <[email protected]>
Co-authored-by: Taekjin LEE <[email protected]>
  • Loading branch information
a-maumau and technolojin authored Dec 16, 2024
1 parent 9ee2c5a commit 496fb5e
Show file tree
Hide file tree
Showing 11 changed files with 103 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,6 @@
filter_scope_max_x: 100.0
filter_scope_max_y: 100.0
filter_scope_max_z: 100.0

# debug parameters
publish_processing_time_detail: false
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <autoware/image_projection_based_fusion/debugger.hpp>
#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware/universe_utils/system/time_keeper.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
Expand Down Expand Up @@ -142,6 +143,11 @@ class FusionNode : public rclcpp::Node
/** \brief processing time publisher. **/
std::unique_ptr<autoware::universe_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;

// timekeeper
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
detailed_processing_time_publisher_;
std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_;
};

} // namespace autoware::image_projection_based_fusion
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ class RoiClusterFusionNode
double fusion_distance_;
double trust_object_distance_;
std::string non_trust_object_iou_mode_{"iou_x"};

bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold);
bool out_of_scope(const DetectedObjectWithFeature & obj) override;
double cal_iou_by_mode(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,10 @@

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

#include <memory>
#include <string>
#include <vector>

namespace autoware::image_projection_based_fusion
{
class RoiPointCloudFusionNode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
#include <image_transport/image_transport.hpp>

#include <memory>
#include <string>
#include <unordered_set>
#include <utility>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ static double processing_time_ms = 0;

namespace autoware::image_projection_based_fusion
{
using autoware::universe_utils::ScopedTimeTrack;

template <class TargetMsg3D, class ObjType, class Msg2D>
FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
Expand Down Expand Up @@ -130,6 +131,17 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
debugger_ =
std::make_shared<Debugger>(this, rois_number_, image_buffer_size, input_camera_topics_);
}

// time keeper
bool use_time_keeper = declare_parameter<bool>("publish_processing_time_detail");
if (use_time_keeper) {
detailed_processing_time_publisher_ =
this->create_publisher<autoware::universe_utils::ProcessingTimeDetail>(
"~/debug/processing_time_detail_ms", 1);
auto time_keeper = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_);
time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(time_keeper);
}

point_project_to_unrectified_image_ =
declare_parameter<bool>("point_project_to_unrectified_image");

Expand Down Expand Up @@ -170,6 +182,9 @@ template <class TargetMsg3D, class Obj, class Msg2D>
void FusionNode<TargetMsg3D, Obj, Msg2D>::subCallback(
const typename TargetMsg3D::ConstSharedPtr input_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

if (cached_msg_.second != nullptr) {
stop_watch_ptr_->toc("processing_time", true);
timer_->cancel();
Expand Down Expand Up @@ -306,6 +321,9 @@ template <class TargetMsg3D, class Obj, class Msg2D>
void FusionNode<TargetMsg3D, Obj, Msg2D>::roiCallback(
const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

stop_watch_ptr_->toc("processing_time", true);

int64_t timestamp_nsec = (*input_roi_msg).header.stamp.sec * static_cast<int64_t>(1e9) +
Expand Down Expand Up @@ -378,6 +396,9 @@ void FusionNode<TargetMsg3D, Obj, Msg2D>::postprocess(TargetMsg3D & output_msg
template <class TargetMsg3D, class Obj, class Msg2D>
void FusionNode<TargetMsg3D, Obj, Msg2D>::timer_callback()
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

using std::chrono_literals::operator""ms;
timer_->cancel();
if (mutex_cached_msgs_.try_lock()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <autoware/lidar_centerpoint/utils.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/math/constants.hpp>
#include <autoware/universe_utils/system/time_keeper.hpp>
#include <pcl_ros/transforms.hpp>

#include <omp.h>
Expand All @@ -35,6 +36,7 @@

namespace
{
using autoware::universe_utils::ScopedTimeTrack;

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

void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) {
RCLCPP_WARN_STREAM_THROTTLE(
this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!");
Expand Down Expand Up @@ -273,6 +278,9 @@ void PointPaintingFusionNode::fuseOnSingleImage(

if (!checkCameraInfo(camera_info)) return;

std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

std::vector<sensor_msgs::msg::RegionOfInterest> debug_image_rois;
std::vector<Eigen::Vector2d> debug_image_points;

Expand Down Expand Up @@ -372,6 +380,10 @@ dc | dc dc dc dc ||zc|
}

if (debugger_) {
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;
if (time_keeper_)
inner_st_ptr = std::make_unique<ScopedTimeTrack>("publish debug message", *time_keeper_);

debugger_->image_rois_ = debug_image_rois;
debugger_->obstacle_points_ = debug_image_points;
debugger_->publishImage(image_id, input_roi_msg.header.stamp);
Expand All @@ -380,6 +392,9 @@ dc | dc dc dc dc ||zc|

void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

const auto objects_sub_count =
obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count();
if (objects_sub_count < 1) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,14 @@

#include <autoware/image_projection_based_fusion/utils/geometry.hpp>
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
#include <autoware/universe_utils/system/time_keeper.hpp>

#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <algorithm>
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>
Expand All @@ -36,6 +38,7 @@

namespace autoware::image_projection_based_fusion
{
using autoware::universe_utils::ScopedTimeTrack;

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

void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluster_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

// reset cluster semantic type
if (!use_cluster_semantic_type_) {
for (auto & feature_object : output_cluster_msg.feature_objects) {
Expand All @@ -67,6 +73,9 @@ void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluste

void RoiClusterFusionNode::postprocess(DetectedObjectsWithFeature & output_cluster_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

if (!remove_unknown_) {
return;
}
Expand All @@ -91,6 +100,9 @@ void RoiClusterFusionNode::fuseOnSingleImage(
{
if (!checkCameraInfo(camera_info)) return;

std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

image_geometry::PinholeCameraModel pinhole_camera_model;
pinhole_camera_model.fromCameraInfo(camera_info);

Expand All @@ -110,6 +122,7 @@ void RoiClusterFusionNode::fuseOnSingleImage(
}

std::map<std::size_t, RegionOfInterest> m_cluster_roi;

for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) {
if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) {
continue;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,17 @@

#include <autoware/image_projection_based_fusion/utils/geometry.hpp>
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
#include <autoware/universe_utils/system/time_keeper.hpp>

#include <algorithm>
#include <map>
#include <memory>
#include <utility>
#include <vector>

namespace autoware::image_projection_based_fusion
{
using autoware::universe_utils::ScopedTimeTrack;

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

void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

std::vector<bool> passthrough_object_flags, fused_object_flags, ignored_object_flags;
passthrough_object_flags.resize(output_msg.objects.size());
fused_object_flags.resize(output_msg.objects.size());
Expand Down Expand Up @@ -81,6 +87,9 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage(
const sensor_msgs::msg::CameraInfo & camera_info,
DetectedObjects & output_object_msg __attribute__((unused)))
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

if (!checkCameraInfo(camera_info)) return;

Eigen::Affine3d object2camera_affine;
Expand Down Expand Up @@ -117,6 +126,9 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
const Eigen::Affine3d & object2camera_affine,
const image_geometry::PinholeCameraModel & pinhole_camera_model)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

std::map<std::size_t, DetectedObjectWithFeature> object_roi_map;
int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast<int64_t>(1e9) +
input_object_msg.header.stamp.nanosec;
Expand Down Expand Up @@ -202,6 +214,9 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage(
const std::vector<DetectedObjectWithFeature> & image_rois,
const std::map<std::size_t, DetectedObjectWithFeature> & object_roi_map)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast<int64_t>(1e9) +
input_object_msg.header.stamp.nanosec;
if (fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@
#include "autoware/image_projection_based_fusion/utils/geometry.hpp"
#include "autoware/image_projection_based_fusion/utils/utils.hpp"

#include <autoware/universe_utils/system/time_keeper.hpp>

#include <memory>
#include <vector>

#ifdef ROS_DISTRO_GALACTIC
Expand All @@ -31,6 +34,8 @@

namespace autoware::image_projection_based_fusion
{
using autoware::universe_utils::ScopedTimeTrack;

RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options)
: FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>(
"roi_pointcloud_fusion", options)
Expand All @@ -47,12 +52,18 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt
void RoiPointCloudFusionNode::preprocess(
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

return;
}

void RoiPointCloudFusionNode::postprocess(
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() +
pub_objects_ptr_->get_intra_process_subscription_count();
if (objects_sub_count < 1) {
Expand Down Expand Up @@ -81,6 +92,9 @@ void RoiPointCloudFusionNode::fuseOnSingleImage(
const sensor_msgs::msg::CameraInfo & camera_info,
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & output_pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

if (input_pointcloud_msg.data.empty()) {
return;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include "autoware/image_projection_based_fusion/utils/geometry.hpp"
#include "autoware/image_projection_based_fusion/utils/utils.hpp"

#include <autoware/universe_utils/system/time_keeper.hpp>
#include <perception_utils/run_length_encoder.hpp>

#include <memory>
Expand All @@ -32,6 +33,8 @@

namespace autoware::image_projection_based_fusion
{
using autoware::universe_utils::ScopedTimeTrack;

SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options)
: FusionNode<PointCloud2, PointCloud2, Image>("segmentation_pointcloud_fusion", options)
{
Expand All @@ -49,11 +52,17 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio

void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

return;
}

void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

auto original_cloud = std::make_shared<PointCloud2>(pointcloud_msg);

int point_step = original_cloud->point_step;
Expand Down Expand Up @@ -82,6 +91,9 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
[[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info,
__attribute__((unused)) PointCloud2 & output_cloud)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

if (input_pointcloud_msg.data.empty()) {
return;
}
Expand Down

0 comments on commit 496fb5e

Please sign in to comment.