Skip to content

Commit 8948859

Browse files
authored
feat(multi_object_tracker): debug timer to work with reduced replay rate recomputation (#6706)
* fix: mot debug timer, full set of timings Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: reduce timers, rename topics Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: separate debugger Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: fix comments Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: fix stamp initialization, remove unused function Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 6e6e601 commit 8948859

File tree

5 files changed

+210
-150
lines changed

5 files changed

+210
-150
lines changed

perception/multi_object_tracker/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ include_directories(
2222
# Generate exe file
2323
set(MULTI_OBJECT_TRACKER_SRC
2424
src/multi_object_tracker_core.cpp
25+
src/debugger.cpp
2526
src/data_association/data_association.cpp
2627
src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp
2728
src/tracker/motion_model/motion_model_base.cpp
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
//
15+
//
16+
17+
#ifndef MULTI_OBJECT_TRACKER__DEBUGGER_HPP_
18+
#define MULTI_OBJECT_TRACKER__DEBUGGER_HPP_
19+
20+
#include <diagnostic_updater/diagnostic_updater.hpp>
21+
#include <diagnostic_updater/publisher.hpp>
22+
#include <rclcpp/rclcpp.hpp>
23+
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
24+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
25+
26+
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
27+
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
28+
#include <geometry_msgs/msg/pose_stamped.hpp>
29+
30+
#include <memory>
31+
32+
/**
33+
* @brief Debugger class for multi object tracker
34+
* @details This class is used to publish debug information of multi object tracker
35+
*/
36+
class TrackerDebugger
37+
{
38+
public:
39+
explicit TrackerDebugger(rclcpp::Node & node);
40+
void publishTentativeObjects(
41+
const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const;
42+
void startMeasurementTime(
43+
const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp);
44+
void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time);
45+
void setupDiagnostics();
46+
void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat);
47+
struct DEBUG_SETTINGS
48+
{
49+
bool publish_processing_time;
50+
bool publish_tentative_objects;
51+
double diagnostics_warn_delay;
52+
double diagnostics_error_delay;
53+
} debug_settings_;
54+
double pipeline_latency_ms_ = 0.0;
55+
diagnostic_updater::Updater diagnostic_updater_;
56+
57+
private:
58+
void loadParameters();
59+
rclcpp::Node & node_;
60+
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr
61+
debug_tentative_objects_pub_;
62+
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;
63+
rclcpp::Time last_input_stamp_;
64+
rclcpp::Time stamp_process_start_;
65+
rclcpp::Time stamp_publish_output_;
66+
};
67+
68+
#endif // MULTI_OBJECT_TRACKER__DEBUGGER_HPP_

perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp

+1-41
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,10 @@
2020
#define MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_
2121

2222
#include "multi_object_tracker/data_association/data_association.hpp"
23+
#include "multi_object_tracker/debugger.hpp"
2324
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
2425

2526
#include <rclcpp/rclcpp.hpp>
26-
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
27-
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
28-
#include <tier4_autoware_utils/system/stop_watch.hpp>
2927

3028
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
3129
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
@@ -41,9 +39,6 @@
4139
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
4240
#endif
4341

44-
#include <diagnostic_updater/diagnostic_updater.hpp>
45-
#include <diagnostic_updater/publisher.hpp>
46-
4742
#include <tf2_ros/buffer.h>
4843
#include <tf2_ros/transform_listener.h>
4944

@@ -53,41 +48,6 @@
5348
#include <string>
5449
#include <vector>
5550

56-
/**
57-
* @brief Debugger class for multi object tracker
58-
* @details This class is used to publish debug information of multi object tracker
59-
*/
60-
class TrackerDebugger
61-
{
62-
public:
63-
explicit TrackerDebugger(rclcpp::Node & node);
64-
void publishProcessingTime();
65-
void publishTentativeObjects(
66-
const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const;
67-
void startStopWatch();
68-
void startMeasurementTime(const rclcpp::Time & measurement_header_stamp);
69-
void setupDiagnostics();
70-
void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat);
71-
struct DEBUG_SETTINGS
72-
{
73-
bool publish_processing_time;
74-
bool publish_tentative_objects;
75-
double diagnostics_warn_delay;
76-
double diagnostics_error_delay;
77-
} debug_settings_;
78-
double elapsed_time_from_sensor_input_ = 0.0;
79-
diagnostic_updater::Updater diagnostic_updater_;
80-
81-
private:
82-
void loadParameters();
83-
rclcpp::Node & node_;
84-
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr
85-
debug_tentative_objects_pub_;
86-
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
87-
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;
88-
rclcpp::Time last_input_stamp_;
89-
};
90-
9151
class MultiObjectTracker : public rclcpp::Node
9252
{
9353
public:
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,138 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
//
15+
//
16+
17+
#include "multi_object_tracker/debugger.hpp"
18+
19+
#include <memory>
20+
21+
TrackerDebugger::TrackerDebugger(rclcpp::Node & node)
22+
: diagnostic_updater_(&node),
23+
node_(node),
24+
last_input_stamp_(node.now()),
25+
stamp_process_start_(node.now()),
26+
stamp_publish_output_(node.now())
27+
{
28+
// declare debug parameters to decide whether to publish debug topics
29+
loadParameters();
30+
// initialize debug publishers
31+
if (debug_settings_.publish_processing_time) {
32+
processing_time_publisher_ =
33+
std::make_unique<tier4_autoware_utils::DebugPublisher>(&node_, "multi_object_tracker");
34+
}
35+
36+
if (debug_settings_.publish_tentative_objects) {
37+
debug_tentative_objects_pub_ =
38+
node_.create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>(
39+
"debug/tentative_objects", rclcpp::QoS{1});
40+
}
41+
42+
// initialize stop watch and diagnostics
43+
setupDiagnostics();
44+
}
45+
46+
void TrackerDebugger::setupDiagnostics()
47+
{
48+
diagnostic_updater_.setHardwareID(node_.get_name());
49+
diagnostic_updater_.add(
50+
"Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay);
51+
diagnostic_updater_.setPeriod(0.1);
52+
}
53+
54+
void TrackerDebugger::loadParameters()
55+
{
56+
try {
57+
debug_settings_.publish_processing_time =
58+
node_.declare_parameter<bool>("publish_processing_time");
59+
debug_settings_.publish_tentative_objects =
60+
node_.declare_parameter<bool>("publish_tentative_objects");
61+
debug_settings_.diagnostics_warn_delay =
62+
node_.declare_parameter<double>("diagnostics_warn_delay");
63+
debug_settings_.diagnostics_error_delay =
64+
node_.declare_parameter<double>("diagnostics_error_delay");
65+
} catch (const std::exception & e) {
66+
RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what());
67+
debug_settings_.publish_processing_time = false;
68+
debug_settings_.publish_tentative_objects = false;
69+
debug_settings_.diagnostics_warn_delay = 0.5;
70+
debug_settings_.diagnostics_error_delay = 1.0;
71+
}
72+
}
73+
74+
void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat)
75+
{
76+
const double delay = pipeline_latency_ms_; // [s]
77+
78+
if (delay == 0.0) {
79+
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated.");
80+
} else if (delay < debug_settings_.diagnostics_warn_delay) {
81+
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is acceptable");
82+
} else if (delay < debug_settings_.diagnostics_error_delay) {
83+
stat.summary(
84+
diagnostic_msgs::msg::DiagnosticStatus::WARN, "Detection delay is over warn threshold.");
85+
} else {
86+
stat.summary(
87+
diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Detection delay is over error threshold.");
88+
}
89+
90+
stat.add("Detection delay", delay);
91+
}
92+
93+
void TrackerDebugger::publishTentativeObjects(
94+
const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const
95+
{
96+
if (debug_settings_.publish_tentative_objects) {
97+
debug_tentative_objects_pub_->publish(tentative_objects);
98+
}
99+
}
100+
101+
void TrackerDebugger::startMeasurementTime(
102+
const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp)
103+
{
104+
last_input_stamp_ = measurement_header_stamp;
105+
stamp_process_start_ = now;
106+
if (debug_settings_.publish_processing_time) {
107+
double input_latency_ms = (now - last_input_stamp_).seconds() * 1e3;
108+
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
109+
"debug/input_latency_ms", input_latency_ms);
110+
}
111+
}
112+
113+
void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time)
114+
{
115+
const auto current_time = now;
116+
// pipeline latency: time from sensor measurement to publish
117+
pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3;
118+
if (debug_settings_.publish_processing_time) {
119+
// processing time: time between input and publish
120+
double processing_time_ms = (current_time - stamp_process_start_).seconds() * 1e3;
121+
// cycle time: time between two consecutive publish
122+
double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3;
123+
// measurement to tracked-object time: time from the sensor measurement to the publishing object
124+
// time If there is not latency compensation, this value is zero
125+
double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3;
126+
127+
// starting from the measurement time
128+
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
129+
"debug/pipeline_latency_ms", pipeline_latency_ms_);
130+
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
131+
"debug/cyclic_time_ms", cyclic_time_ms);
132+
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
133+
"debug/processing_time_ms", processing_time_ms);
134+
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
135+
"debug/meas_to_tracked_object_ms", measurement_to_object_ms);
136+
}
137+
stamp_publish_output_ = current_time;
138+
}

0 commit comments

Comments
 (0)