@@ -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" );
@@ -179,7 +184,7 @@ void MultiObjectTracker::onMeasurement(
179
184
}
180
185
181
186
/* life cycle check */
182
- checkTrackerLifeCycle (list_tracker_, measurement_time, *self_transform );
187
+ checkTrackerLifeCycle (list_tracker_, measurement_time);
183
188
/* sanitize trackers */
184
189
sanitizeTracker (list_tracker_, measurement_time);
185
190
@@ -198,7 +203,14 @@ void MultiObjectTracker::onMeasurement(
198
203
199
204
// Publish objects if the timer is not enabled
200
205
if (publish_timer_ == nullptr ) {
206
+ // Publish if the delay compensation is disabled
201
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
+ }
202
214
}
203
215
}
204
216
@@ -232,24 +244,32 @@ std::shared_ptr<Tracker> MultiObjectTracker::createNewTracker(
232
244
void MultiObjectTracker::onTimer ()
233
245
{
234
246
const rclcpp::Time current_time = this ->now ();
235
- const auto self_transform =
236
- getTransformAnonymous (tf_buffer_, world_frame_id_, " base_link" , current_time);
237
- if (!self_transform) {
238
- 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);
239
254
}
255
+ }
240
256
257
+ void MultiObjectTracker::checkAndPublish (const rclcpp::Time & time)
258
+ {
241
259
/* life cycle check */
242
- checkTrackerLifeCycle (list_tracker_, current_time, *self_transform );
260
+ checkTrackerLifeCycle (list_tracker_, time );
243
261
/* sanitize trackers */
244
- sanitizeTracker (list_tracker_, current_time );
262
+ sanitizeTracker (list_tracker_, time );
245
263
246
264
// Publish
247
- publish (current_time);
265
+ publish (time );
266
+
267
+ // Update last published time
268
+ last_published_time_ = this ->now ();
248
269
}
249
270
250
271
void MultiObjectTracker::checkTrackerLifeCycle (
251
- std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
252
- [[maybe_unused]] const geometry_msgs::msg::Transform & self_transform)
272
+ std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time)
253
273
{
254
274
/* params */
255
275
constexpr float max_elapsed_time = 1.0 ;
0 commit comments