Skip to content

Commit df69515

Browse files
committed
feat: add validation for consecutive delay time
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
1 parent 508a449 commit df69515

File tree

3 files changed

+68
-16
lines changed

3 files changed

+68
-16
lines changed

perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -56,3 +56,4 @@
5656
publish_processing_time_detail: false
5757
publish_debug_markers: false
5858
processing_time_tolerance_ms: 500.0 #[ms]
59+
consecutive_delay_tolerance_ms: 1000.0 #[ms]

perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
#include <deque>
4747
#include <map>
4848
#include <memory>
49+
#include <mutex>
4950
#include <optional>
5051
#include <string>
5152
#include <unordered_map>
@@ -118,7 +119,11 @@ class MapBasedPredictionNode : public rclcpp::Node
118119

119120
// Diagnostics
120121
std::unique_ptr<autoware_utils::DiagnosticsInterface> diagnostics_interface_ptr_;
122+
rclcpp::TimerBase::SharedPtr diagnostics_timer_;
121123
double processing_time_tolerance_ms_;
124+
double consecutive_delay_tolerance_ms_;
125+
std::optional<rclcpp::Time> last_intime_processing_timestamp_;
126+
std::mutex diagnostics_mtx_;
122127

123128
////// Parameters
124129

@@ -168,6 +173,9 @@ class MapBasedPredictionNode : public rclcpp::Node
168173
void trafficSignalsCallback(const TrafficLightGroupArray::ConstSharedPtr msg);
169174
void objectsCallback(const TrackedObjects::ConstSharedPtr in_objects);
170175

176+
// Diagnostics callback
177+
void diagnosticsTimerCallback();
178+
171179
// Map process
172180
bool doesPathCrossFence(
173181
const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line);

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+59-16
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,8 @@
5151
#include <functional>
5252
#include <limits>
5353
#include <memory>
54+
#include <mutex>
55+
#include <ratio>
5456
#include <sstream>
5557
#include <string>
5658
#include <utility>
@@ -486,10 +488,18 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
486488
stop_watch_ptr_->tic("cyclic_time");
487489
stop_watch_ptr_->tic("processing_time");
488490

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+
}
493503

494504
// debug publishers
495505
if (use_time_publisher) {
@@ -542,6 +552,30 @@ rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam(
542552
return result;
543553
}
544554

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+
545579
void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg)
546580
{
547581
RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Start loading lanelet");
@@ -679,19 +713,28 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
679713
const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
680714

681715
// 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);
693737
}
694-
diagnostics_interface_ptr_->publish(output.header.stamp);
695738

696739
// Publish Processing Time
697740
if (processing_time_publisher_) {

0 commit comments

Comments
 (0)