@@ -194,7 +194,8 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
194
194
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this );
195
195
// Diagnostics
196
196
diagnostics_interface_ptr_ =
197
- std::make_unique<autoware_utils::DiagnosticsInterface>(this , " multi_object_tracker" );
197
+ std::make_unique<autoware_utils::DiagnosticsInterface>(this , " multi_object_tracker_delay_compensation" );
198
+
198
199
}
199
200
200
201
void MultiObjectTracker::onTrigger ()
@@ -242,14 +243,19 @@ void MultiObjectTracker::onTimer()
242
243
const double maximum_publish_interval = publisher_period_ * maximum_publish_interval_ratio;
243
244
should_publish = should_publish || elapsed_time > maximum_publish_interval;
244
245
246
+ const double warning_publish_interval = publisher_period_ * warning_publish_interval_ratio;
247
+
245
248
diagnostics_interface_ptr_->clear ();
246
249
diagnostics_interface_ptr_->add_key_value (" elapsed_time" , elapsed_time);
247
- if (elapsed_time > 500e-3 ) {
250
+ if (elapsed_time > warning_publish_interval ) {
248
251
std::stringstream message;
249
- message << " MultiObjectTracker::onTimer: elapsed_time exceeds its maximum value, "
250
- << " which may limit the predition performance." ;
252
+ message << " MultiObjectTracker::onTimer: elapsed_time exceeds its maximum value, " << warning_publish_interval;
251
253
diagnostics_interface_ptr_->update_level_and_message (
252
254
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str ());
255
+ } else {
256
+ diagnostics_interface_ptr_->update_level_and_message (
257
+ diagnostic_msgs::msg::DiagnosticStatus::OK, " OK" );
258
+
253
259
}
254
260
diagnostics_interface_ptr_->publish (current_time);
255
261
0 commit comments