Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add diagnostic handler to warn the processing time excess #10219

Draft
wants to merge 1 commit into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/ros/debug_publisher.hpp>
#include <autoware_utils/ros/diagnostics_interface.hpp>
#include <autoware_utils/ros/polling_subscriber.hpp>
#include <autoware_utils/ros/published_time_publisher.hpp>
#include <autoware_utils/ros/transform_listener.hpp>
Expand Down Expand Up @@ -115,6 +116,9 @@ class MapBasedPredictionNode : public rclcpp::Node
// Predictor
std::shared_ptr<PredictorVru> predictor_vru_;

// Diagnostics handler
std::unique_ptr<autoware_utils::DiagnosticsInterface> diagnostics_interface_ptr_;

////// Parameters

//// Vehicle Parameters
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <autoware_utils/ros/uuid_helper.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include <boost/geometry.hpp>
Expand All @@ -50,6 +51,7 @@
#include <functional>
#include <limits>
#include <memory>
#include <sstream>
#include <string>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -497,6 +499,10 @@
time_keeper_ = std::make_shared<autoware_utils::TimeKeeper>(time_keeper);
path_generator_->setTimeKeeper(time_keeper_);
predictor_vru_->setTimeKeeper(time_keeper_);

// diagnostics handler
diagnostics_interface_ptr_ =
std::make_unique<autoware_utils::DiagnosticsInterface>(this, "map_based_prediction");

Check warning on line 505 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MapBasedPredictionNode::MapBasedPredictionNode increases from 120 to 122 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
}

if (use_debug_marker) {
Expand Down Expand Up @@ -671,6 +677,19 @@
"debug/cyclic_time_ms", cyclic_time_ms);
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);

diagnostics_interface_ptr_->clear();
constexpr double processing_time_threshold_ms = 500.0; // TODO(ktro2828): Use parameter value
bool is_processing_time = processing_time_ms > processing_time_threshold_ms;
diagnostics_interface_ptr_->add_key_value("is_processing_time", is_processing_time);
if (is_processing_time) {
std::ostringstream oss;
oss << "Processing time exceeded " << processing_time_threshold_ms << "[ms] < "
<< processing_time_ms << "[ms]";
diagnostics_interface_ptr_->update_level_and_message(
diagnostic_msgs::msg::DiagnosticStatus::WARN, oss.str());
}

Check warning on line 691 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp#L690-L691

Added lines #L690 - L691 were not covered by tests
diagnostics_interface_ptr_->publish(output.header.stamp);

Check warning on line 692 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::objectsCallback increases in cyclomatic complexity from 20 to 21, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}
}

Expand Down
Loading