@@ -68,6 +68,7 @@ boost::optional<geometry_msgs::msg::Transform> getTransformAnonymous(
68
68
69
69
MultiObjectTracker::MultiObjectTracker (const rclcpp::NodeOptions & node_options)
70
70
: rclcpp::Node(" multi_object_tracker" , node_options),
71
+ last_published_time_(this ->now ()),
71
72
tf_buffer_(this ->get_clock ()),
72
73
tf_listener_(tf_buffer_)
73
74
{
@@ -83,7 +84,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
83
84
create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>(" output" , rclcpp::QoS{1 });
84
85
85
86
// Parameters
86
- double publish_rate = declare_parameter<double >(" publish_rate" );
87
+ double publish_rate = declare_parameter<double >(" publish_rate" ); // [hz]
87
88
world_frame_id_ = declare_parameter<std::string>(" world_frame_id" );
88
89
bool enable_delay_compensation{declare_parameter<bool >(" enable_delay_compensation" )};
89
90
@@ -94,11 +95,15 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
94
95
this ->get_node_base_interface (), this ->get_node_timers_interface ());
95
96
tf_buffer_.setCreateTimerInterface (cti);
96
97
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.
98
101
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 ();
100
105
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 ));
102
107
}
103
108
104
109
const auto tmp = this ->declare_parameter <std::vector<int64_t >>(" can_assign_matrix" );
@@ -135,10 +140,14 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
135
140
void MultiObjectTracker::onMeasurement (
136
141
const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg)
137
142
{
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
+
138
147
/* 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 );
142
151
if (!self_transform) {
143
152
return ;
144
153
}
@@ -150,7 +159,6 @@ void MultiObjectTracker::onMeasurement(
150
159
return ;
151
160
}
152
161
/* tracker prediction */
153
- const rclcpp::Time measurement_time = input_objects_msg->header .stamp ;
154
162
for (auto itr = list_tracker_.begin (); itr != list_tracker_.end (); ++itr) {
155
163
(*itr)->predict (measurement_time);
156
164
}
@@ -176,7 +184,7 @@ void MultiObjectTracker::onMeasurement(
176
184
}
177
185
178
186
/* life cycle check */
179
- checkTrackerLifeCycle (list_tracker_, measurement_time, *self_transform );
187
+ checkTrackerLifeCycle (list_tracker_, measurement_time);
180
188
/* sanitize trackers */
181
189
sanitizeTracker (list_tracker_, measurement_time);
182
190
@@ -190,8 +198,19 @@ void MultiObjectTracker::onMeasurement(
190
198
if (tracker) list_tracker_.push_back (tracker);
191
199
}
192
200
201
+ // debugger time
202
+ debugger_->endMeasurementTime (this ->now ());
203
+
204
+ // Publish objects if the timer is not enabled
193
205
if (publish_timer_ == nullptr ) {
206
+ // Publish if the delay compensation is disabled
194
207
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
+ }
195
214
}
196
215
}
197
216
@@ -225,24 +244,32 @@ std::shared_ptr<Tracker> MultiObjectTracker::createNewTracker(
225
244
void MultiObjectTracker::onTimer ()
226
245
{
227
246
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);
232
254
}
255
+ }
233
256
257
+ void MultiObjectTracker::checkAndPublish (const rclcpp::Time & time)
258
+ {
234
259
/* life cycle check */
235
- checkTrackerLifeCycle (list_tracker_, current_time, *self_transform );
260
+ checkTrackerLifeCycle (list_tracker_, time );
236
261
/* sanitize trackers */
237
- sanitizeTracker (list_tracker_, current_time );
262
+ sanitizeTracker (list_tracker_, time );
238
263
239
264
// Publish
240
- publish (current_time);
265
+ publish (time );
266
+
267
+ // Update last published time
268
+ last_published_time_ = this ->now ();
241
269
}
242
270
243
271
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)
246
273
{
247
274
/* params */
248
275
constexpr float max_elapsed_time = 1.0 ;
@@ -337,6 +364,7 @@ inline bool MultiObjectTracker::shouldTrackerPublish(
337
364
338
365
void MultiObjectTracker::publish (const rclcpp::Time & time) const
339
366
{
367
+ debugger_->startPublishTime (this ->now ());
340
368
const auto subscriber_count = tracked_objects_pub_->get_subscription_count () +
341
369
tracked_objects_pub_->get_intra_process_subscription_count ();
342
370
if (subscriber_count < 1 ) {
0 commit comments