Skip to content

Commit f6857bf

Browse files
technolojinesteve
authored andcommittedApr 9, 2024
fix(multi_object_tracker): mot timer bug fix (#6775)
* fix: set object timestamp type to follow node time fix: remove comment Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: add initialization checkers Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: timestamp initialization Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent c1b145b commit f6857bf

File tree

2 files changed

+32
-19
lines changed

2 files changed

+32
-19
lines changed
 

‎perception/multi_object_tracker/src/debugger.cpp

+25-15
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,7 @@
1818

1919
#include <memory>
2020

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())
21+
TrackerDebugger::TrackerDebugger(rclcpp::Node & node) : diagnostic_updater_(&node), node_(node)
2722
{
2823
// declare debug parameters to decide whether to publish debug topics
2924
loadParameters();
@@ -39,7 +34,15 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node)
3934
"debug/tentative_objects", rclcpp::QoS{1});
4035
}
4136

42-
// initialize stop watch and diagnostics
37+
// initialize timestamps
38+
const rclcpp::Time now = node_.now();
39+
last_input_stamp_ = now;
40+
stamp_process_start_ = now;
41+
stamp_process_end_ = now;
42+
stamp_publish_start_ = now;
43+
stamp_publish_output_ = now;
44+
45+
// setup diagnostics
4346
setupDiagnostics();
4447
}
4548

@@ -73,7 +76,11 @@ void TrackerDebugger::loadParameters()
7376

7477
void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat)
7578
{
76-
const double delay = pipeline_latency_ms_; // [s]
79+
if (!is_initialized_) {
80+
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Measurement time is not set.");
81+
return;
82+
}
83+
const double & delay = pipeline_latency_ms_; // [s]
7784

7885
if (delay == 0.0) {
7986
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated.");
@@ -127,18 +134,21 @@ void TrackerDebugger::startPublishTime(const rclcpp::Time & now)
127134

128135
void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time)
129136
{
130-
const auto current_time = now;
137+
// if the measurement time is not set, do not publish debug information
138+
if (!is_initialized_) return;
139+
131140
// pipeline latency: time from sensor measurement to publish, used for 'checkDelay'
132-
pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3;
133-
if (debug_settings_.publish_processing_time && is_initialized_) {
141+
pipeline_latency_ms_ = (now - last_input_stamp_).seconds() * 1e3;
142+
143+
if (debug_settings_.publish_processing_time) {
134144
// processing latency: time between input and publish
135-
double processing_latency_ms = ((current_time - stamp_process_start_).seconds()) * 1e3;
145+
double processing_latency_ms = ((now - stamp_process_start_).seconds()) * 1e3;
136146
// processing time: only the time spent in the tracking processes
137-
double processing_time_ms = ((current_time - stamp_publish_start_).seconds() +
147+
double processing_time_ms = ((now - stamp_publish_start_).seconds() +
138148
(stamp_process_end_ - stamp_process_start_).seconds()) *
139149
1e3;
140150
// cycle time: time between two consecutive publish
141-
double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3;
151+
double cyclic_time_ms = (now - stamp_publish_output_).seconds() * 1e3;
142152
// measurement to tracked-object time: time from the sensor measurement to the publishing object
143153
// time If there is not latency compensation, this value is zero
144154
double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3;
@@ -155,5 +165,5 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim
155165
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
156166
"debug/meas_to_tracked_object_ms", measurement_to_object_ms);
157167
}
158-
stamp_publish_output_ = current_time;
168+
stamp_publish_output_ = now;
159169
}

‎perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -135,10 +135,14 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
135135
void MultiObjectTracker::onMeasurement(
136136
const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg)
137137
{
138+
// Get the time of the measurement
139+
const rclcpp::Time measurement_time =
140+
rclcpp::Time(input_objects_msg->header.stamp, this->now().get_clock_type());
141+
138142
/* keep the latest input stamp and check transform*/
139-
debugger_->startMeasurementTime(this->now(), rclcpp::Time(input_objects_msg->header.stamp));
140-
const auto self_transform = getTransformAnonymous(
141-
tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp);
143+
debugger_->startMeasurementTime(this->now(), measurement_time);
144+
const auto self_transform =
145+
getTransformAnonymous(tf_buffer_, "base_link", world_frame_id_, measurement_time);
142146
if (!self_transform) {
143147
return;
144148
}
@@ -150,7 +154,6 @@ void MultiObjectTracker::onMeasurement(
150154
return;
151155
}
152156
/* tracker prediction */
153-
const rclcpp::Time measurement_time = input_objects_msg->header.stamp;
154157
for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) {
155158
(*itr)->predict(measurement_time);
156159
}

0 commit comments

Comments
 (0)