|
51 | 51 | #include <functional>
|
52 | 52 | #include <limits>
|
53 | 53 | #include <memory>
|
| 54 | +#include <mutex> |
| 55 | +#include <ratio> |
54 | 56 | #include <sstream>
|
55 | 57 | #include <string>
|
56 | 58 | #include <utility>
|
@@ -486,10 +488,18 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
|
486 | 488 | stop_watch_ptr_->tic("cyclic_time");
|
487 | 489 | stop_watch_ptr_->tic("processing_time");
|
488 | 490 |
|
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"); |
| 491 | + { // diagnostics |
| 492 | + using std::chrono_literals::operator""ms; |
| 493 | + |
| 494 | + diagnostics_interface_ptr_ = |
| 495 | + std::make_unique<autoware_utils::DiagnosticsInterface>(this, "map_based_prediction"); |
| 496 | + |
| 497 | + diagnostics_timer_ = |
| 498 | + create_wall_timer(100ms, std::bind(&MapBasedPredictionNode::diagnosticsTimerCallback, this)); |
| 499 | + |
| 500 | + processing_time_tolerance_ms_ = declare_parameter<double>("processing_time_tolerance_ms"); |
| 501 | + consecutive_delay_tolerance_ms_ = declare_parameter<double>("consecutive_delay_tolerance_ms"); |
| 502 | + } |
493 | 503 |
|
494 | 504 | // debug publishers
|
495 | 505 | if (use_time_publisher) {
|
@@ -542,6 +552,30 @@ rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam(
|
542 | 552 | return result;
|
543 | 553 | }
|
544 | 554 |
|
| 555 | +void MapBasedPredictionNode::diagnosticsTimerCallback() |
| 556 | +{ |
| 557 | + std::lock_guard<std::mutex> lock(diagnostics_mtx_); |
| 558 | + if (last_intime_processing_timestamp_) { |
| 559 | + diagnostics_interface_ptr_->clear(); |
| 560 | + const auto timestamp_now = get_clock()->now(); |
| 561 | + const double delay_duration = |
| 562 | + std::chrono::duration<double, std::milli>( |
| 563 | + std::chrono::nanoseconds( |
| 564 | + (timestamp_now - last_intime_processing_timestamp_.value()).nanoseconds())) |
| 565 | + .count(); |
| 566 | + |
| 567 | + bool is_processing_time_exceeds_consecutively = |
| 568 | + delay_duration > consecutive_delay_tolerance_ms_; |
| 569 | + diagnostics_interface_ptr_->add_key_value( |
| 570 | + "is_processing_time_exceeds_consecutively", is_processing_time_exceeds_consecutively); |
| 571 | + if (is_processing_time_exceeds_consecutively) { |
| 572 | + diagnostics_interface_ptr_->update_level_and_message( |
| 573 | + diagnostic_msgs::msg::DiagnosticStatus::ERROR, ""); |
| 574 | + } |
| 575 | + diagnostics_interface_ptr_->publish(timestamp_now); |
| 576 | + } |
| 577 | +} |
| 578 | + |
545 | 579 | void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg)
|
546 | 580 | {
|
547 | 581 | RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Start loading lanelet");
|
@@ -679,19 +713,28 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
|
679 | 713 | const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
|
680 | 714 |
|
681 | 715 | // Diagnostics
|
682 |
| - diagnostics_interface_ptr_->clear(); |
683 |
| - diagnostics_interface_ptr_->add_key_value("processing_time_ms", processing_time_ms); |
684 |
| - bool is_processing_time_exceeds_tolerance = processing_time_ms > processing_time_tolerance_ms_; |
685 |
| - diagnostics_interface_ptr_->add_key_value( |
686 |
| - "is_processing_time_exceeds_tolerance", is_processing_time_exceeds_tolerance); |
687 |
| - if (is_processing_time_exceeds_tolerance) { |
688 |
| - std::ostringstream oss; |
689 |
| - oss << "Processing time exceeded " << processing_time_tolerance_ms_ << "[ms] < " |
690 |
| - << processing_time_ms << "[ms]"; |
691 |
| - diagnostics_interface_ptr_->update_level_and_message( |
692 |
| - diagnostic_msgs::msg::DiagnosticStatus::WARN, oss.str()); |
| 716 | + { |
| 717 | + std::lock_guard<std::mutex> lock(diagnostics_mtx_); |
| 718 | + diagnostics_interface_ptr_->clear(); |
| 719 | + diagnostics_interface_ptr_->add_key_value("processing_time_ms", processing_time_ms); |
| 720 | + bool is_processing_time_exceeds_tolerance = processing_time_ms > processing_time_tolerance_ms_; |
| 721 | + diagnostics_interface_ptr_->add_key_value( |
| 722 | + "is_processing_time_exceeds_tolerance", is_processing_time_exceeds_tolerance); |
| 723 | + if (is_processing_time_exceeds_tolerance) { |
| 724 | + std::ostringstream oss; |
| 725 | + oss << "Processing time exceeded " << processing_time_tolerance_ms_ << "[ms] < " |
| 726 | + << processing_time_ms << "[ms]"; |
| 727 | + diagnostics_interface_ptr_->update_level_and_message( |
| 728 | + diagnostic_msgs::msg::DiagnosticStatus::WARN, oss.str()); |
| 729 | + |
| 730 | + if (!last_intime_processing_timestamp_) { |
| 731 | + last_intime_processing_timestamp_ = get_clock()->now(); |
| 732 | + } |
| 733 | + } else { |
| 734 | + last_intime_processing_timestamp_ = get_clock()->now(); |
| 735 | + } |
| 736 | + diagnostics_interface_ptr_->publish(output.header.stamp); |
693 | 737 | }
|
694 |
| - diagnostics_interface_ptr_->publish(output.header.stamp); |
695 | 738 |
|
696 | 739 | // Publish Processing Time
|
697 | 740 | if (processing_time_publisher_) {
|
|
0 commit comments