Skip to content

Commit 3070120

Browse files
author
lei.gu
committed
feat(multi_object_tracker): add warning_publish_interval_ratio
1 parent 6f70512 commit 3070120

File tree

2 files changed

+11
-4
lines changed

2 files changed

+11
-4
lines changed

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp

+10-4
Original file line numberDiff line numberDiff line change
@@ -194,7 +194,8 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
194194
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this);
195195
// Diagnostics
196196
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+
198199
}
199200

200201
void MultiObjectTracker::onTrigger()
@@ -242,14 +243,19 @@ void MultiObjectTracker::onTimer()
242243
const double maximum_publish_interval = publisher_period_ * maximum_publish_interval_ratio;
243244
should_publish = should_publish || elapsed_time > maximum_publish_interval;
244245

246+
const double warning_publish_interval = publisher_period_ * warning_publish_interval_ratio;
247+
245248
diagnostics_interface_ptr_->clear();
246249
diagnostics_interface_ptr_->add_key_value("elapsed_time", elapsed_time);
247-
if (elapsed_time > 500e-3) {
250+
if (elapsed_time > warning_publish_interval) {
248251
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;
251253
diagnostics_interface_ptr_->update_level_and_message(
252254
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+
253259
}
254260
diagnostics_interface_ptr_->publish(current_time);
255261

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,7 @@ class MultiObjectTracker : public rclcpp::Node
8080
double publisher_period_;
8181
static constexpr double minimum_publish_interval_ratio = 0.85;
8282
static constexpr double maximum_publish_interval_ratio = 1.05;
83+
static constexpr double warning_publish_interval_ratio = 1.30;
8384

8485
// internal states
8586
std::string world_frame_id_; // tracking frame

0 commit comments

Comments
 (0)