Skip to content

Commit 283d13d

Browse files
committed
feat: add diagnostic handler to warn when the processing time exceed a threshold
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
1 parent b7acf99 commit 283d13d

File tree

2 files changed

+23
-0
lines changed

2 files changed

+23
-0
lines changed

perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include <autoware_utils/geometry/geometry.hpp>
2323
#include <autoware_utils/ros/debug_publisher.hpp>
24+
#include <autoware_utils/ros/diagnostics_interface.hpp>
2425
#include <autoware_utils/ros/polling_subscriber.hpp>
2526
#include <autoware_utils/ros/published_time_publisher.hpp>
2627
#include <autoware_utils/ros/transform_listener.hpp>
@@ -115,6 +116,9 @@ class MapBasedPredictionNode : public rclcpp::Node
115116
// Predictor
116117
std::shared_ptr<PredictorVru> predictor_vru_;
117118

119+
// Diagnostics handler
120+
std::unique_ptr<autoware_utils::DiagnosticsInterface> diagnostics_interface_ptr_;
121+
118122
////// Parameters
119123

120124
//// Vehicle Parameters

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
#include <autoware_utils/ros/uuid_helper.hpp>
3131

3232
#include <autoware_perception_msgs/msg/detected_objects.hpp>
33+
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
3334
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
3435

3536
#include <boost/geometry.hpp>
@@ -50,6 +51,7 @@
5051
#include <functional>
5152
#include <limits>
5253
#include <memory>
54+
#include <sstream>
5355
#include <string>
5456
#include <utility>
5557
#include <vector>
@@ -497,6 +499,10 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
497499
time_keeper_ = std::make_shared<autoware_utils::TimeKeeper>(time_keeper);
498500
path_generator_->setTimeKeeper(time_keeper_);
499501
predictor_vru_->setTimeKeeper(time_keeper_);
502+
503+
// diagnostics handler
504+
diagnostics_interface_ptr_ =
505+
std::make_unique<autoware_utils::DiagnosticsInterface>(this, "map_based_prediction");
500506
}
501507

502508
if (use_debug_marker) {
@@ -671,6 +677,19 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
671677
"debug/cyclic_time_ms", cyclic_time_ms);
672678
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
673679
"debug/processing_time_ms", processing_time_ms);
680+
681+
diagnostics_interface_ptr_->clear();
682+
constexpr double processing_time_threshold_ms = 500.0; // TODO(ktro2828): Use parameter value
683+
bool is_processing_time = processing_time_ms > processing_time_threshold_ms;
684+
diagnostics_interface_ptr_->add_key_value("is_processing_time", is_processing_time);
685+
if (is_processing_time) {
686+
std::ostringstream oss;
687+
oss << "Processing time exceeded " << processing_time_threshold_ms << "[ms] < "
688+
<< processing_time_ms << "[ms]";
689+
diagnostics_interface_ptr_->update_level_and_message(
690+
diagnostic_msgs::msg::DiagnosticStatus::WARN, oss.str());
691+
}
692+
diagnostics_interface_ptr_->publish(output.header.stamp);
674693
}
675694
}
676695

0 commit comments

Comments
 (0)