Skip to content

Commit 4f814c2

Browse files
authored
Merge pull request #1236 from technolojin/tmp/mot-timer-cherrypicks
fix(multi_object_tracker): mot timer cherrypicks
2 parents df0e170 + ddc1ec1 commit 4f814c2

File tree

4 files changed

+105
-36
lines changed

4 files changed

+105
-36
lines changed

perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,10 @@ class TrackerDebugger
4141
const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const;
4242
void startMeasurementTime(
4343
const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp);
44+
void endMeasurementTime(const rclcpp::Time & now);
45+
void startPublishTime(const rclcpp::Time & now);
4446
void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time);
47+
4548
void setupDiagnostics();
4649
void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat);
4750
struct DEBUG_SETTINGS
@@ -56,12 +59,15 @@ class TrackerDebugger
5659

5760
private:
5861
void loadParameters();
62+
bool is_initialized_ = false;
5963
rclcpp::Node & node_;
6064
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr
6165
debug_tentative_objects_pub_;
6266
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;
6367
rclcpp::Time last_input_stamp_;
6468
rclcpp::Time stamp_process_start_;
69+
rclcpp::Time stamp_process_end_;
70+
rclcpp::Time stamp_publish_start_;
6571
rclcpp::Time stamp_publish_output_;
6672
};
6773

perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,11 @@ class MultiObjectTracker : public rclcpp::Node
5858
tracked_objects_pub_;
5959
rclcpp::Subscription<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr
6060
detected_object_sub_;
61-
rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer
61+
62+
// publish timer
63+
rclcpp::TimerBase::SharedPtr publish_timer_;
64+
rclcpp::Time last_published_time_;
65+
double publisher_period_;
6266

6367
// debugger class
6468
std::unique_ptr<TrackerDebugger> debugger_;
@@ -79,14 +83,14 @@ class MultiObjectTracker : public rclcpp::Node
7983
std::unique_ptr<DataAssociation> data_association_;
8084

8185
void checkTrackerLifeCycle(
82-
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
83-
const geometry_msgs::msg::Transform & self_transform);
86+
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time);
8487
void sanitizeTracker(
8588
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time);
8689
std::shared_ptr<Tracker> createNewTracker(
8790
const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
8891
const geometry_msgs::msg::Transform & self_transform) const;
8992

93+
void checkAndPublish(const rclcpp::Time & time);
9094
void publish(const rclcpp::Time & time) const;
9195
inline bool shouldTrackerPublish(const std::shared_ptr<const Tracker> tracker) const;
9296
};

perception/multi_object_tracker/src/debugger.cpp

+46-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.");
@@ -108,18 +115,40 @@ void TrackerDebugger::startMeasurementTime(
108115
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
109116
"debug/input_latency_ms", input_latency_ms);
110117
}
118+
// initialize debug time stamps
119+
if (!is_initialized_) {
120+
stamp_publish_output_ = now;
121+
is_initialized_ = true;
122+
}
123+
}
124+
125+
void TrackerDebugger::endMeasurementTime(const rclcpp::Time & now)
126+
{
127+
stamp_process_end_ = now;
128+
}
129+
130+
void TrackerDebugger::startPublishTime(const rclcpp::Time & now)
131+
{
132+
stamp_publish_start_ = now;
111133
}
112134

113135
void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time)
114136
{
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;
137+
// if the measurement time is not set, do not publish debug information
138+
if (!is_initialized_) return;
139+
140+
// pipeline latency: time from sensor measurement to publish, used for 'checkDelay'
141+
pipeline_latency_ms_ = (now - last_input_stamp_).seconds() * 1e3;
142+
118143
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;
144+
// processing latency: time between input and publish
145+
double processing_latency_ms = ((now - stamp_process_start_).seconds()) * 1e3;
146+
// processing time: only the time spent in the tracking processes
147+
double processing_time_ms = ((now - stamp_publish_start_).seconds() +
148+
(stamp_process_end_ - stamp_process_start_).seconds()) *
149+
1e3;
121150
// cycle time: time between two consecutive publish
122-
double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3;
151+
double cyclic_time_ms = (now - stamp_publish_output_).seconds() * 1e3;
123152
// measurement to tracked-object time: time from the sensor measurement to the publishing object
124153
// time If there is not latency compensation, this value is zero
125154
double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3;
@@ -131,8 +160,10 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim
131160
"debug/cyclic_time_ms", cyclic_time_ms);
132161
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
133162
"debug/processing_time_ms", processing_time_ms);
163+
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
164+
"debug/processing_latency_ms", processing_latency_ms);
134165
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
135166
"debug/meas_to_tracked_object_ms", measurement_to_object_ms);
136167
}
137-
stamp_publish_output_ = current_time;
168+
stamp_publish_output_ = now;
138169
}

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+46-18
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@ boost::optional<geometry_msgs::msg::Transform> getTransformAnonymous(
6868

6969
MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
7070
: rclcpp::Node("multi_object_tracker", node_options),
71+
last_published_time_(this->now()),
7172
tf_buffer_(this->get_clock()),
7273
tf_listener_(tf_buffer_)
7374
{
@@ -83,7 +84,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
8384
create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>("output", rclcpp::QoS{1});
8485

8586
// Parameters
86-
double publish_rate = declare_parameter<double>("publish_rate");
87+
double publish_rate = declare_parameter<double>("publish_rate"); // [hz]
8788
world_frame_id_ = declare_parameter<std::string>("world_frame_id");
8889
bool enable_delay_compensation{declare_parameter<bool>("enable_delay_compensation")};
8990

@@ -94,11 +95,15 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
9495
this->get_node_base_interface(), this->get_node_timers_interface());
9596
tf_buffer_.setCreateTimerInterface(cti);
9697

97-
// Create ROS time based timer
98+
// Create ROS time based timer.
99+
// If the delay compensation is enabled, the timer is used to publish the output at the correct
100+
// time.
98101
if (enable_delay_compensation) {
99-
const auto period_ns = rclcpp::Rate(publish_rate).period();
102+
publisher_period_ = 1.0 / publish_rate; // [s]
103+
constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check
104+
const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period();
100105
publish_timer_ = rclcpp::create_timer(
101-
this, get_clock(), period_ns, std::bind(&MultiObjectTracker::onTimer, this));
106+
this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this));
102107
}
103108

104109
const auto tmp = this->declare_parameter<std::vector<int64_t>>("can_assign_matrix");
@@ -135,10 +140,14 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
135140
void MultiObjectTracker::onMeasurement(
136141
const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg)
137142
{
143+
// Get the time of the measurement
144+
const rclcpp::Time measurement_time =
145+
rclcpp::Time(input_objects_msg->header.stamp, this->now().get_clock_type());
146+
138147
/* 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);
148+
debugger_->startMeasurementTime(this->now(), measurement_time);
149+
const auto self_transform =
150+
getTransformAnonymous(tf_buffer_, "base_link", world_frame_id_, measurement_time);
142151
if (!self_transform) {
143152
return;
144153
}
@@ -150,7 +159,6 @@ void MultiObjectTracker::onMeasurement(
150159
return;
151160
}
152161
/* tracker prediction */
153-
const rclcpp::Time measurement_time = input_objects_msg->header.stamp;
154162
for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) {
155163
(*itr)->predict(measurement_time);
156164
}
@@ -176,7 +184,7 @@ void MultiObjectTracker::onMeasurement(
176184
}
177185

178186
/* life cycle check */
179-
checkTrackerLifeCycle(list_tracker_, measurement_time, *self_transform);
187+
checkTrackerLifeCycle(list_tracker_, measurement_time);
180188
/* sanitize trackers */
181189
sanitizeTracker(list_tracker_, measurement_time);
182190

@@ -190,8 +198,19 @@ void MultiObjectTracker::onMeasurement(
190198
if (tracker) list_tracker_.push_back(tracker);
191199
}
192200

201+
// debugger time
202+
debugger_->endMeasurementTime(this->now());
203+
204+
// Publish objects if the timer is not enabled
193205
if (publish_timer_ == nullptr) {
206+
// Publish if the delay compensation is disabled
194207
publish(measurement_time);
208+
} else {
209+
// Publish if the next publish time is close
210+
const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period
211+
if ((this->now() - last_published_time_).seconds() > minimum_publish_interval) {
212+
checkAndPublish(this->now());
213+
}
195214
}
196215
}
197216

@@ -225,24 +244,32 @@ std::shared_ptr<Tracker> MultiObjectTracker::createNewTracker(
225244
void MultiObjectTracker::onTimer()
226245
{
227246
const rclcpp::Time current_time = this->now();
228-
const auto self_transform =
229-
getTransformAnonymous(tf_buffer_, world_frame_id_, "base_link", current_time);
230-
if (!self_transform) {
231-
return;
247+
// check the publish period
248+
const auto elapsed_time = (current_time - last_published_time_).seconds();
249+
// if the elapsed time is over the period, publish objects with prediction
250+
constexpr double maximum_latency_ratio = 1.11; // 11% margin
251+
const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio;
252+
if (elapsed_time > maximum_publish_latency) {
253+
checkAndPublish(current_time);
232254
}
255+
}
233256

257+
void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time)
258+
{
234259
/* life cycle check */
235-
checkTrackerLifeCycle(list_tracker_, current_time, *self_transform);
260+
checkTrackerLifeCycle(list_tracker_, time);
236261
/* sanitize trackers */
237-
sanitizeTracker(list_tracker_, current_time);
262+
sanitizeTracker(list_tracker_, time);
238263

239264
// Publish
240-
publish(current_time);
265+
publish(time);
266+
267+
// Update last published time
268+
last_published_time_ = this->now();
241269
}
242270

243271
void MultiObjectTracker::checkTrackerLifeCycle(
244-
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
245-
[[maybe_unused]] const geometry_msgs::msg::Transform & self_transform)
272+
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time)
246273
{
247274
/* params */
248275
constexpr float max_elapsed_time = 1.0;
@@ -337,6 +364,7 @@ inline bool MultiObjectTracker::shouldTrackerPublish(
337364

338365
void MultiObjectTracker::publish(const rclcpp::Time & time) const
339366
{
367+
debugger_->startPublishTime(this->now());
340368
const auto subscriber_count = tracked_objects_pub_->get_subscription_count() +
341369
tracked_objects_pub_->get_intra_process_subscription_count();
342370
if (subscriber_count < 1) {

0 commit comments

Comments
 (0)