@@ -189,13 +189,12 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
189
189
}
190
190
191
191
// Debugger
192
- debugger_ = std::make_unique<TrackerDebugger>(*this , world_frame_id_,input_channels_config_);
192
+ debugger_ = std::make_unique<TrackerDebugger>(*this , world_frame_id_, input_channels_config_);
193
193
194
194
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this );
195
195
// Diagnostics
196
- diagnostics_interface_ptr_ =
197
- std::make_unique<autoware_utils::DiagnosticsInterface>(this , " multi_object_tracker_delay_compensation" );
198
-
196
+ diagnostics_interface_ptr_ = std::make_unique<autoware_utils::DiagnosticsInterface>(
197
+ this , " multi_object_tracker_delay_compensation" );
199
198
}
200
199
201
200
void MultiObjectTracker::onTrigger ()
@@ -249,13 +248,13 @@ void MultiObjectTracker::onTimer()
249
248
diagnostics_interface_ptr_->add_key_value (" elapsed_time" , elapsed_time);
250
249
if (elapsed_time > warning_publish_interval) {
251
250
std::stringstream message;
252
- message << " MultiObjectTracker::onTimer: elapsed_time exceeds its maximum value, " << warning_publish_interval;
251
+ message << " MultiObjectTracker::onTimer: elapsed_time exceeds its maximum value, "
252
+ << warning_publish_interval;
253
253
diagnostics_interface_ptr_->update_level_and_message (
254
254
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str ());
255
255
} else {
256
- diagnostics_interface_ptr_->update_level_and_message (
257
- diagnostic_msgs::msg::DiagnosticStatus::OK, " OK" );
258
-
256
+ diagnostics_interface_ptr_->update_level_and_message (
257
+ diagnostic_msgs::msg::DiagnosticStatus::OK, " OK" );
259
258
}
260
259
diagnostics_interface_ptr_->publish (current_time);
261
260
0 commit comments