@@ -481,13 +481,24 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
481
481
// publishers
482
482
pub_objects_ = this ->create_publisher <PredictedObjects>(" ~/output/objects" , rclcpp::QoS{1 });
483
483
484
+ // stopwatch
485
+ stop_watch_ptr_ = std::make_unique<autoware_utils::StopWatch<std::chrono::milliseconds>>();
486
+ stop_watch_ptr_->tic (" cyclic_time" );
487
+ stop_watch_ptr_->tic (" processing_time" );
488
+
489
+ // diagnostics
490
+ diagnostics_interface_ptr_ =
491
+ std::make_unique<autoware_utils::DiagnosticsInterface>(this , " map_based_prediction" );
492
+ processing_time_tolerance_ms_ = declare_parameter<double >(" processing_time_tolerance_ms" );
493
+
484
494
// debug publishers
485
495
if (use_time_publisher) {
486
496
processing_time_publisher_ =
487
497
std::make_unique<autoware_utils::DebugPublisher>(this , " map_based_prediction" );
488
498
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this );
489
499
}
490
500
501
+ // debug time keeper
491
502
if (use_time_keeper) {
492
503
detailed_processing_time_publisher_ =
493
504
this ->create_publisher <autoware_utils::ProcessingTimeDetail>(
@@ -498,16 +509,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
498
509
predictor_vru_->setTimeKeeper (time_keeper_);
499
510
}
500
511
501
- // diagnostics
502
- diagnostics_interface_ptr_ =
503
- std::make_unique<autoware_utils::DiagnosticsInterface>(this , " map_based_prediction" );
504
- processing_time_tolerance_ms_ = declare_parameter<double >(" processing_time_tolerance_ms" );
505
-
506
- // stopwatch
507
- stop_watch_ptr_ = std::make_unique<autoware_utils::StopWatch<std::chrono::milliseconds>>();
508
- stop_watch_ptr_->tic (" cyclic_time" );
509
- stop_watch_ptr_->tic (" processing_time" );
510
-
512
+ // debug marker
511
513
if (use_debug_marker) {
512
514
pub_debug_markers_ =
513
515
this ->create_publisher <visualization_msgs::msg::MarkerArray>(" maneuver" , rclcpp::QoS{1 });
@@ -678,6 +680,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
678
680
679
681
// Diagnostics
680
682
diagnostics_interface_ptr_->clear ();
683
+ diagnostics_interface_ptr_->add_key_value (" processing_time_ms" , processing_time_ms);
681
684
bool is_processing_time_exceeds_tolerance = processing_time_ms > processing_time_tolerance_ms_;
682
685
diagnostics_interface_ptr_->add_key_value (
683
686
" is_processing_time_exceeds_tolerance" , is_processing_time_exceeds_tolerance);
0 commit comments