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(multi_object_tracker): add debugger output processing_time/cyclic_time/elapsed_time, tentative objects #5762

Merged
merged 4 commits into from
Dec 11, 2023
Merged
Show file tree
Hide file tree
Changes from 2 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 @@ -23,6 +23,8 @@
#include "multi_object_tracker/tracker/model/tracker_base.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 <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
Expand Down Expand Up @@ -59,6 +61,12 @@ class MultiObjectTracker : public rclcpp::Node
detected_object_sub_;
rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer

// debug publishers
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr
debug_tentative_objects_pub_;
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_;

yukkysaito marked this conversation as resolved.
Show resolved Hide resolved
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

Expand All @@ -71,6 +79,8 @@ class MultiObjectTracker : public rclcpp::Node
std::string world_frame_id_; // tracking frame
std::list<std::shared_ptr<Tracker>> list_tracker_;
std::unique_ptr<DataAssociation> data_association_;
bool debug_flag_;
rclcpp::Time last_input_stamp_;

void checkTrackerLifeCycle(
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
Expand Down
47 changes: 44 additions & 3 deletions perception/multi_object_tracker/src/multi_object_tracker_core.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in perception/multi_object_tracker/src/multi_object_tracker_core.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.00 to 6.22, 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 @@ -68,7 +68,8 @@
MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
: rclcpp::Node("multi_object_tracker", node_options),
tf_buffer_(this->get_clock()),
tf_listener_(tf_buffer_)
tf_listener_(tf_buffer_),
last_input_stamp_(this->now())

Check warning on line 72 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#L71-L72

Added lines #L71 - L72 were not covered by tests
{
// Create publishers and subscribers
detected_object_sub_ = create_subscription<autoware_auto_perception_msgs::msg::DetectedObjects>(
Expand All @@ -81,6 +82,19 @@
double publish_rate = declare_parameter<double>("publish_rate", 30.0);
world_frame_id_ = declare_parameter<std::string>("world_frame_id", "world");
bool enable_delay_compensation{declare_parameter("enable_delay_compensation", false)};
debug_flag_ = declare_parameter<bool>("debug_flag", false);

Check warning on line 85 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#L85

Added line #L85 was not covered by tests
miursh marked this conversation as resolved.
Show resolved Hide resolved

// Debug publishers
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");
if (debug_flag_) {

Check warning on line 91 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#L88-L91

Added lines #L88 - L91 were not covered by tests
debug_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "multi_object_tracker");

Check warning on line 93 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#L93

Added line #L93 was not covered by tests
debug_tentative_objects_pub_ =
create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>(
"debug/tentative_objects", rclcpp::QoS{1});

Check warning on line 96 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#L95-L96

Added lines #L95 - L96 were not covered by tests
}

auto cti = std::make_shared<tf2_ros::CreateTimerROS>(
this->get_node_base_interface(), this->get_node_timers_interface());
Expand Down Expand Up @@ -126,6 +140,9 @@
void MultiObjectTracker::onMeasurement(
const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg)
{
/* keep the latest input stamp and check transform*/
last_input_stamp_ = rclcpp::Time(input_objects_msg->header.stamp);
stop_watch_ptr_->toc("processing_time", true);

Check warning on line 145 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#L144-L145

Added lines #L144 - L145 were not covered by tests
const auto self_transform = getTransformAnonymous(
tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp);
if (!self_transform) {
Expand Down Expand Up @@ -332,11 +349,16 @@
return;
}
// Create output msg
autoware_auto_perception_msgs::msg::TrackedObjects output_msg;
autoware_auto_perception_msgs::msg::TrackedObjects output_msg, tentative_objects_msg;
output_msg.header.frame_id = world_frame_id_;
output_msg.header.stamp = time;
tentative_objects_msg.header = output_msg.header;

for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) {
if (!shouldTrackerPublish(*itr)) {
if (!shouldTrackerPublish(*itr)) { // for debug purpose
autoware_auto_perception_msgs::msg::TrackedObject object;
(*itr)->getTrackedObject(time, object);
tentative_objects_msg.objects.push_back(object);

Check warning on line 361 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#L358-L361

Added lines #L358 - L361 were not covered by tests
continue;
}
autoware_auto_perception_msgs::msg::TrackedObject object;
Expand All @@ -346,6 +368,25 @@

// Publish
tracked_objects_pub_->publish(output_msg);

if (debug_flag_) {

Check warning on line 372 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#L372

Added line #L372 was not covered by tests
// Publish debug info
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
miursh marked this conversation as resolved.
Show resolved Hide resolved
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(

Check warning on line 376 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#L374-L376

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

Check warning on line 378 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#L378

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

// Publish delay time
const rclcpp::Time current_time = this->now();
const double elapsed_time_from_sensor_input = (current_time - last_input_stamp_).nanoseconds();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/elapsed_time_from_sensor_input_ms", elapsed_time_from_sensor_input * 1e-6);

Check warning on line 385 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#L382-L385

Added lines #L382 - L385 were not covered by tests

// Publish tentative objects
debug_tentative_objects_pub_->publish(tentative_objects_msg);
}

Check warning on line 389 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#L388-L389

Added lines #L388 - L389 were not covered by tests
}

RCLCPP_COMPONENTS_REGISTER_NODE(MultiObjectTracker)
Loading