Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(map_based_prediction, etc): publish processing time in various perception nodes #6574

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp>
#include <rclcpp/rclcpp.hpp>
#include <shape_estimation/shape_estimator.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
Expand Down Expand Up @@ -61,6 +63,11 @@
divided_objects_pub_ =
node->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"debug/divided_objects", 1);
processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(node, "detection_by_tracker");

Check warning on line 67 in perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp#L67

Added line #L67 was not covered by tests
stop_watch_ptr_ =
std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
this->startStopWatch();

Check warning on line 70 in perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp#L69-L70

Added lines #L69 - L70 were not covered by tests
}

~Debugger() {}
Expand All @@ -80,6 +87,19 @@
{
divided_objects_pub_->publish(removeFeature(input));
}
void startStopWatch()

Check warning on line 90 in perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp#L90

Added line #L90 was not covered by tests
{
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}
void startMeasureProcessingTime() { stop_watch_ptr_->tic("processing_time"); }
void publishProcessingTime()

Check warning on line 96 in perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp#L92-L96

Added lines #L92 - L96 were not covered by tests
{
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true));
}

Check warning on line 102 in perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp#L98-L102

Added lines #L98 - L102 were not covered by tests

private:
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
Expand All @@ -90,6 +110,9 @@
merged_objects_pub_;
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
divided_objects_pub_;
// debug publisher
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;

autoware_auto_perception_msgs::msg::DetectedObjects removeFeature(
const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,7 @@
void DetectionByTracker::onObjects(
const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg)
{
debugger_->startMeasureProcessingTime();
autoware_auto_perception_msgs::msg::DetectedObjects detected_objects;
detected_objects.header = input_msg->header;

Expand Down Expand Up @@ -250,6 +251,7 @@
}

objects_pub_->publish(detected_objects);
debugger_->publishProcessingTime();

Check warning on line 254 in perception/detection_by_tracker/src/detection_by_tracker_core.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/src/detection_by_tracker_core.cpp#L254

Added line #L254 was not covered by tests
}

void DetectionByTracker::divideUnderSegmentedObjects(
Expand Down
12 changes: 7 additions & 5 deletions perception/map_based_prediction/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -218,11 +218,13 @@ If the target object is inside the road or crosswalk, this module outputs one or

### Output

| Name | Type | Description |
| ------------------------ | ------------------------------------------------------ | ------------------------------------------------------------------------------------- |
| `~/input/objects` | `autoware_auto_perception_msgs::msg::TrackedObjects` | tracking objects. Default is set to `/perception/object_recognition/tracking/objects` |
| `~/output/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | tracking objects with predicted path. |
| `~/objects_path_markers` | `visualization_msgs::msg::MarkerArray` | marker for visualization. |
| Name | Type | Description |
| ---------------------------- | ------------------------------------------------------ | ------------------------------------------------------------------------------------- |
| `~/input/objects` | `autoware_auto_perception_msgs::msg::TrackedObjects` | tracking objects. Default is set to `/perception/object_recognition/tracking/objects` |
| `~/output/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | tracking objects with predicted path. |
| `~/objects_path_markers` | `visualization_msgs::msg::MarkerArray` | marker for visualization. |
| `~/debug/processing_time_ms` | `std_msgs::msg::Float64` | processing time of this module. |
| `~/debug/cyclic_time_ms` | `std_msgs::msg::Float64` | cyclic time of this module. |

## Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "tier4_autoware_utils/ros/update_param.hpp"

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/transform_listener.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>
Expand All @@ -33,7 +34,6 @@
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <tier4_debug_msgs/msg/string_stamped.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <lanelet2_core/Forward.h>
Expand Down Expand Up @@ -125,11 +125,14 @@ class MapBasedPredictionNode : public rclcpp::Node
// ROS Publisher and Subscriber
rclcpp::Publisher<PredictedObjects>::SharedPtr pub_objects_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_debug_markers_;
rclcpp::Publisher<StringStamped>::SharedPtr pub_calculation_time_;
rclcpp::Subscription<TrackedObjects>::SharedPtr sub_objects_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<TrafficSignalArray>::SharedPtr sub_traffic_signals_;

// debug publisher
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;

// Object History
std::unordered_map<std::string, std::deque<ObjectData>> objects_history_;
std::map<std::pair<std::string, lanelet::Id>, rclcpp::Time> stopped_times_against_green_;
Expand Down Expand Up @@ -196,9 +199,6 @@ class MapBasedPredictionNode : public rclcpp::Node
std::vector<double> distance_set_for_no_intention_to_walk_;
std::vector<double> timeout_set_for_no_intention_to_walk_;

// Stop watch
StopWatch<std::chrono::milliseconds> stop_watch_;

// Member Functions
void mapCallback(const HADMapBin::ConstSharedPtr msg);
void trafficSignalsCallback(const TrafficSignalArray::ConstSharedPtr msg);
Expand Down
25 changes: 13 additions & 12 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1768 to 1769, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 6.42 to 6.52, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -646,14 +646,6 @@
}
}

StringStamped createStringStamped(const rclcpp::Time & now, const double data)
{
StringStamped msg;
msg.stamp = now;
msg.data = std::to_string(data);
return msg;
}

// NOTE: These two functions are copied from the route_handler package.
lanelet::Lanelets getRightOppositeLanelets(
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
Expand Down Expand Up @@ -816,10 +808,15 @@
pub_objects_ = this->create_publisher<PredictedObjects>("~/output/objects", rclcpp::QoS{1});
pub_debug_markers_ =
this->create_publisher<visualization_msgs::msg::MarkerArray>("maneuver", rclcpp::QoS{1});
pub_calculation_time_ = create_publisher<StringStamped>("~/debug/calculation_time", 1);
processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "map_based_prediction");

Check warning on line 812 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L812

Added line #L812 was not covered by tests

set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1));

stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");

Check warning on line 819 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MapBasedPredictionNode::MapBasedPredictionNode increases from 84 to 88 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 819 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L817-L819

Added lines #L817 - L819 were not covered by tests
}

rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam(
Expand Down Expand Up @@ -893,7 +890,7 @@

void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects)
{
stop_watch_.tic();
stop_watch_ptr_->toc("processing_time", true);

Check warning on line 893 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L893

Added line #L893 was not covered by tests
// Guard for map pointer and frame transformation
if (!lanelet_map_ptr_) {
return;
Expand Down Expand Up @@ -1116,8 +1113,12 @@
// Publish Results
pub_objects_->publish(output);
pub_debug_markers_->publish(debug_markers);
const auto calculation_time_msg = createStringStamped(now(), stop_watch_.toc());
pub_calculation_time_->publish(calculation_time_msg);
const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(

Check warning on line 1118 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1116-L1118

Added lines #L1116 - L1118 were not covered by tests
"debug/cyclic_time_ms", cyclic_time_ms);
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(

Check warning on line 1120 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1120

Added line #L1120 was not covered by tests
"debug/processing_time_ms", processing_time_ms);

Check warning on line 1121 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::objectsCallback already has high cyclomatic complexity, and now it increases in Lines of Code from 173 to 177. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}

bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/elapsed_time_from_sensor_input_ms", elapsed_time_from_sensor_input_ * 1e3);
"debug/pipeline_latency_ms", elapsed_time_from_sensor_input_ * 1e3);

Check warning on line 151 in perception/multi_object_tracker/src/multi_object_tracker_core.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/multi_object_tracker_core.cpp#L151

Added line #L151 was not covered by tests
}
}

Expand Down
6 changes: 6 additions & 0 deletions perception/object_merger/include/object_merger/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include "object_merger/data_association/data_association.hpp"

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

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>

Expand Down Expand Up @@ -81,6 +83,10 @@ class ObjectAssociationMergerNode : public rclcpp::Node
std::map<int, double> generalized_iou_threshold;
std::map<int /*class label*/, double /*distance_threshold*/> distance_threshold_map;
} overlapped_judge_param_;

// debug publisher
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
};
} // namespace object_association

Expand Down
13 changes: 13 additions & 0 deletions perception/object_merger/src/object_association_merger/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,13 @@

merged_object_pub_ = create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"output/object", rclcpp::QoS{1});

// Debug publisher
processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "object_association_merger");
stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");

Check warning on line 127 in perception/object_merger/src/object_association_merger/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/object_merger/src/object_association_merger/node.cpp#L124-L127

Added lines #L124 - L127 were not covered by tests
}

void ObjectAssociationMergerNode::objectsCallback(
Expand All @@ -128,6 +135,7 @@
if (merged_object_pub_->get_subscription_count() < 1) {
return;
}
stop_watch_ptr_->toc("processing_time", true);

Check warning on line 138 in perception/object_merger/src/object_association_merger/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/object_merger/src/object_association_merger/node.cpp#L138

Added line #L138 was not covered by tests

/* transform to base_link coordinate */
autoware_auto_perception_msgs::msg::DetectedObjects transformed_objects0, transformed_objects1;
Expand Down Expand Up @@ -215,6 +223,11 @@

// publish output msg
merged_object_pub_->publish(output_msg);
// publish processing time
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true));

Check notice on line 230 in perception/object_merger/src/object_association_merger/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

ObjectAssociationMergerNode::objectsCallback already has high cyclomatic complexity, and now it increases in Lines of Code from 84 to 89. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 230 in perception/object_merger/src/object_association_merger/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/object_merger/src/object_association_merger/node.cpp#L227-L230

Added lines #L227 - L230 were not covered by tests
}
} // namespace object_association

Expand Down
12 changes: 12 additions & 0 deletions perception/shape_estimation/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,17 @@
RCLCPP_INFO(this->get_logger(), "using boost shape estimation : %d", use_boost_bbox_optimizer);
estimator_ =
std::make_unique<ShapeEstimator>(use_corrector, use_filter, use_boost_bbox_optimizer);

processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "shape_estimation");
stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");

Check warning on line 58 in perception/shape_estimation/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L55-L58

Added lines #L55 - L58 were not covered by tests
}

void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstSharedPtr input_msg)
{
stop_watch_ptr_->toc("processing_time", true);

Check warning on line 63 in perception/shape_estimation/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L63

Added line #L63 was not covered by tests
// Guard
if (pub_->get_subscription_count() < 1) {
return;
Expand Down Expand Up @@ -108,6 +115,11 @@

// Publish
pub_->publish(output_msg);

processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true));

Check warning on line 122 in perception/shape_estimation/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L119-L122

Added lines #L119 - L122 were not covered by tests
}

#include <rclcpp_components/register_node_macro.hpp>
Expand Down
6 changes: 6 additions & 0 deletions perception/shape_estimation/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include "shape_estimation/shape_estimator.hpp"

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

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
Expand All @@ -33,6 +35,10 @@ class ShapeEstimationNode : public rclcpp::Node
rclcpp::Publisher<DetectedObjectsWithFeature>::SharedPtr pub_;
rclcpp::Subscription<DetectedObjectsWithFeature>::SharedPtr sub_;

// debug publisher
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;

void callback(const DetectedObjectsWithFeature::ConstSharedPtr input_msg);

std::unique_ptr<ShapeEstimator> estimator_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include "tracking_object_merger/utils/utils.hpp"

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

#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
#include <std_msgs/msg/header.hpp>
Expand Down Expand Up @@ -87,6 +89,8 @@ class DecorativeTrackerMergerNode : public rclcpp::Node
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr
debug_object_pub_;
bool publish_interpolated_sub_objects_;
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;

/* handle objects */
std::unordered_map<MEASUREMENT_STATE, std::function<void(TrackedObject &, const TrackedObject &)>>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,13 @@
set3dDataAssociation("lidar-radar", data_association_map_);
// radar-radar association matrix
set3dDataAssociation("radar-radar", data_association_map_);

// debug publisher
processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "decorative_object_merger_node");
stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");

Check warning on line 160 in perception/tracking_object_merger/src/decorative_tracker_merger.cpp

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/decorative_tracker_merger.cpp#L157-L160

Added lines #L157 - L160 were not covered by tests
}

void DecorativeTrackerMergerNode::set3dDataAssociation(
Expand Down Expand Up @@ -182,6 +189,7 @@
void DecorativeTrackerMergerNode::mainObjectsCallback(
const TrackedObjects::ConstSharedPtr & main_objects)
{
stop_watch_ptr_->toc("processing_time", true);

Check warning on line 192 in perception/tracking_object_merger/src/decorative_tracker_merger.cpp

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/decorative_tracker_merger.cpp#L192

Added line #L192 was not covered by tests
// try to merge sub object
if (!sub_objects_buffer_.empty()) {
// get interpolated sub objects
Expand Down Expand Up @@ -214,6 +222,10 @@
this->decorativeMerger(main_sensor_type_, main_objects);

merged_object_pub_->publish(getTrackedObjects(main_objects->header));
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true));
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true));

Check warning on line 228 in perception/tracking_object_merger/src/decorative_tracker_merger.cpp

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/decorative_tracker_merger.cpp#L225-L228

Added lines #L225 - L228 were not covered by tests
}

/**
Expand Down
Loading