From 328ffa9fb4c6ab0084ffcc65f8a428ed32252431 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Tue, 15 Oct 2024 17:54:28 +0900 Subject: [PATCH] feat(costmap_generator, control_validator, scenario_selector, surround_obstacle_checker, vehicle_cmd_gate): add processing time pub. (#9065) * feat(costmap_generator, control_validator, scenario_selector, surround_obstacle_checker, vehicle_cmd_gate): Add: processing_time_pub Signed-off-by: Kazunori-Nakajima * fix: pre-commit Signed-off-by: Kasunori-Nakajima * feat(costmap_generator): fix: No output when not Active. Signed-off-by: Kasunori-Nakajima * fix: clang-format Signed-off-by: Kasunori-Nakajima * Re: fix: clang-format Signed-off-by: Kasunori-Nakajima --------- Signed-off-by: Kazunori-Nakajima Signed-off-by: Kasunori-Nakajima --- .../control_validator/control_validator.hpp | 5 +++++ .../src/control_validator.cpp | 11 ++++++++++ .../src/vehicle_cmd_gate.cpp | 22 +++++++++++++++++++ .../src/vehicle_cmd_gate.hpp | 6 +++++ .../costmap_generator.hpp | 7 ++++++ .../costmap_generator_node.cpp | 14 ++++++++++++ .../autoware/scenario_selector/node.hpp | 6 +++++ .../autoware_scenario_selector/src/node.cpp | 11 ++++++++++ .../src/node.cpp | 11 ++++++++++ .../src/node.hpp | 2 ++ .../config/processing_time_checker.param.yaml | 5 +++++ 11 files changed, 100 insertions(+) diff --git a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp index 56a1e39391b10..551ee08aa3327 100644 --- a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp +++ b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp @@ -20,12 +20,14 @@ #include "autoware_vehicle_info_utils/vehicle_info.hpp" #include "diagnostic_updater/diagnostic_updater.hpp" +#include #include #include #include #include #include +#include #include #include @@ -143,6 +145,7 @@ class ControlValidator : public rclcpp::Node universe_utils::InterProcessPollingSubscriber::SharedPtr sub_reference_traj_; rclcpp::Publisher::SharedPtr pub_status_; rclcpp::Publisher::SharedPtr pub_markers_; + rclcpp::Publisher::SharedPtr pub_processing_time_; // system parameters int64_t diag_error_count_threshold_ = 0; @@ -167,6 +170,8 @@ class ControlValidator : public rclcpp::Node Odometry::ConstSharedPtr current_kinematics_; + autoware::universe_utils::StopWatch stop_watch; + std::shared_ptr debug_pose_publisher_; }; } // namespace autoware::control_validator diff --git a/control/autoware_control_validator/src/control_validator.cpp b/control/autoware_control_validator/src/control_validator.cpp index 2370d274fecc8..d601319d47bc5 100644 --- a/control/autoware_control_validator/src/control_validator.cpp +++ b/control/autoware_control_validator/src/control_validator.cpp @@ -47,6 +47,9 @@ ControlValidator::ControlValidator(const rclcpp::NodeOptions & options) pub_markers_ = create_publisher("~/output/markers", 1); + pub_processing_time_ = + this->create_publisher("~/debug/processing_time_ms", 1); + debug_pose_publisher_ = std::make_shared(this); setup_parameters(); @@ -134,6 +137,8 @@ bool ControlValidator::is_data_ready() void ControlValidator::on_predicted_trajectory(const Trajectory::ConstSharedPtr msg) { + stop_watch.tic(); + current_predicted_trajectory_ = msg; current_reference_trajectory_ = sub_reference_traj_->takeData(); current_kinematics_ = sub_kinematics_->takeData(); @@ -162,6 +167,12 @@ void ControlValidator::publish_debug_info() debug_pose_publisher_->push_warning_msg(front_pose, "INVALID CONTROL"); } debug_pose_publisher_->publish(); + + // Publish ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_->publish(processing_time_msg); } void ControlValidator::validate( diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index bf61b69857849..b028455ab3354 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -77,6 +77,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) engage_pub_ = create_publisher("output/engage", durable_qos); pub_external_emergency_ = create_publisher("output/external_emergency", durable_qos); operation_mode_pub_ = create_publisher("output/operation_mode", durable_qos); + processing_time_pub_ = + this->create_publisher("~/debug/processing_time_ms", 1); is_filter_activated_pub_ = create_publisher("~/is_filter_activated", durable_qos); @@ -375,6 +377,8 @@ T VehicleCmdGate::getContinuousTopic( void VehicleCmdGate::onTimer() { + stop_watch.tic(); + // Subscriber for auto const auto msg_auto_command_turn_indicator = auto_turn_indicator_cmd_sub_.takeData(); if (msg_auto_command_turn_indicator) @@ -573,12 +577,18 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands) vehicle_cmd_emergency.emergency = (use_emergency_handling_ && is_system_emergency_); vehicle_cmd_emergency.stamp = filtered_control.stamp; + // ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + // Publish commands vehicle_cmd_emergency_pub_->publish(vehicle_cmd_emergency); control_cmd_pub_->publish(filtered_control); published_time_publisher_->publish_if_subscribed(control_cmd_pub_, filtered_control.stamp); adapi_pause_->publish(); moderate_stop_interface_->publish(); + processing_time_pub_->publish(processing_time_msg); // Save ControlCmd to steering angle when disengaged prev_control_cmd_ = filtered_control; @@ -616,12 +626,18 @@ void VehicleCmdGate::publishEmergencyStopControlCommands() vehicle_cmd_emergency.stamp = stamp; vehicle_cmd_emergency.emergency = true; + // ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + // Publish topics vehicle_cmd_emergency_pub_->publish(vehicle_cmd_emergency); control_cmd_pub_->publish(control_cmd); turn_indicator_cmd_pub_->publish(turn_indicator); hazard_light_cmd_pub_->publish(hazard_light); gear_cmd_pub_->publish(gear); + processing_time_pub_->publish(processing_time_msg); } void VehicleCmdGate::publishStatus() @@ -638,12 +654,18 @@ void VehicleCmdGate::publishStatus() external_emergency.stamp = stamp; external_emergency.emergency = is_external_emergency_stop_; + // ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + gate_mode_pub_->publish(current_gate_mode_); engage_pub_->publish(autoware_engage); pub_external_emergency_->publish(external_emergency); operation_mode_pub_->publish(current_operation_mode_); adapi_pause_->publish(); moderate_stop_interface_->publish(); + processing_time_pub_->publish(processing_time_msg); } Control VehicleCmdGate::filterControlCommand(const Control & in) diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 6863015443363..c2716ea3baa6a 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include #include @@ -41,6 +42,7 @@ #include #include #include +#include #include #include #include @@ -114,6 +116,7 @@ class VehicleCmdGate : public rclcpp::Node rclcpp::Publisher::SharedPtr filter_activated_marker_pub_; rclcpp::Publisher::SharedPtr filter_activated_marker_raw_pub_; rclcpp::Publisher::SharedPtr filter_activated_flag_pub_; + rclcpp::Publisher::SharedPtr processing_time_pub_; // Parameter callback OnSetParametersCallbackHandle::SharedPtr set_param_res_; rcl_interfaces::msg::SetParametersResult onParameter( @@ -268,6 +271,9 @@ class VehicleCmdGate : public rclcpp::Node std::unique_ptr vehicle_stop_checker_; double stop_check_duration_; + // processing time + autoware::universe_utils::StopWatch stop_watch; + // debug MarkerArray createMarkerArray(const IsFilterActivated & filter_activated); void publishMarkers(const IsFilterActivated & filter_activated); diff --git a/planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp index b08d16c68fa6f..434440359f282 100644 --- a/planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp @@ -49,6 +49,8 @@ #include "autoware_costmap_generator/points_to_costmap.hpp" #include "costmap_generator_node_parameters.hpp" +#include +#include #include #include #include @@ -58,6 +60,7 @@ #include #include #include +#include #include #include @@ -91,6 +94,7 @@ class CostmapGenerator : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_costmap_; rclcpp::Publisher::SharedPtr pub_occupancy_grid_; rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr pub_processing_time_ms_; rclcpp::Subscription::SharedPtr sub_points_; rclcpp::Subscription::SharedPtr sub_objects_; @@ -175,6 +179,9 @@ class CostmapGenerator : public rclcpp::Node /// \brief calculate cost for final output grid_map::Matrix generateCombinedCostmap(); + + /// \brief measure processing time + autoware::universe_utils::StopWatch stop_watch; }; } // namespace autoware::costmap_generator diff --git a/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp index 9012b7f3250b4..07bf9eb33ffbe 100644 --- a/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp @@ -192,6 +192,8 @@ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options) pub_processing_time_ = create_publisher("processing_time", 1); time_keeper_ = std::make_shared(pub_processing_time_); + pub_processing_time_ms_ = + this->create_publisher("~/debug/processing_time_ms", 1); // Timer const auto period_ns = rclcpp::Rate(param_->update_rate).period(); @@ -277,7 +279,13 @@ void CostmapGenerator::onScenario(const tier4_planning_msgs::msg::Scenario::Cons void CostmapGenerator::onTimer() { autoware::universe_utils::ScopedTimeTrack scoped_time_track(__func__, *time_keeper_); + stop_watch.tic(); if (!isActive()) { + // Publish ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_ms_->publish(processing_time_msg); return; } @@ -467,6 +475,12 @@ void CostmapGenerator::publishCostmap(const grid_map::GridMap & costmap) auto out_gridmap_msg = grid_map::GridMapRosConverter::toMessage(costmap); out_gridmap_msg->header = header; pub_costmap_->publish(*out_gridmap_msg); + + // Publish ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_ms_->publish(processing_time_msg); } } // namespace autoware::costmap_generator diff --git a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp index 487c643fe5673..244876ee2cb22 100644 --- a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp +++ b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include @@ -37,6 +38,7 @@ #endif #include #include +#include #include #include @@ -95,6 +97,7 @@ class ScenarioSelectorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_parking_trajectory_; rclcpp::Publisher::SharedPtr pub_trajectory_; rclcpp::Publisher::SharedPtr pub_scenario_; + rclcpp::Publisher::SharedPtr pub_processing_time_; // polling subscribers universe_utils::InterProcessPollingSubscriber< @@ -130,6 +133,9 @@ class ScenarioSelectorNode : public rclcpp::Node static constexpr double lane_stopping_timeout_s = 5.0; static constexpr double empty_parking_trajectory_timeout_s = 3.0; + + // processing time + autoware::universe_utils::StopWatch stop_watch; }; } // namespace autoware::scenario_selector #endif // AUTOWARE__SCENARIO_SELECTOR__NODE_HPP_ diff --git a/planning/autoware_scenario_selector/src/node.cpp b/planning/autoware_scenario_selector/src/node.cpp index 1f4547d04c8fc..eb3303766205f 100644 --- a/planning/autoware_scenario_selector/src/node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -330,6 +330,9 @@ bool ScenarioSelectorNode::isDataReady() void ScenarioSelectorNode::updateData() { + { + stop_watch.tic(); + } { auto msg = sub_parking_state_->takeData(); is_parking_completed_ = msg ? msg->data : is_parking_completed_; @@ -370,6 +373,12 @@ void ScenarioSelectorNode::onTimer() } pub_scenario_->publish(scenario); + + // Publish ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_->publish(processing_time_msg); } void ScenarioSelectorNode::onLaneDrivingTrajectory( @@ -466,6 +475,8 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti this, get_clock(), period_ns, std::bind(&ScenarioSelectorNode::onTimer, this)); published_time_publisher_ = std::make_unique(this); + pub_processing_time_ = + this->create_publisher("~/debug/processing_time_ms", 1); } } // namespace autoware::scenario_selector diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 719a507ab569b..da0dd0ec09a26 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -109,6 +110,8 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio "~/output/velocity_limit_clear_command", rclcpp::QoS{1}.transient_local()); pub_velocity_limit_ = this->create_publisher( "~/output/max_velocity", rclcpp::QoS{1}.transient_local()); + pub_processing_time_ = + this->create_publisher("~/debug/processing_time_ms", 1); using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( @@ -151,6 +154,9 @@ bool SurroundObstacleCheckerNode::getUseDynamicObject() const void SurroundObstacleCheckerNode::onTimer() { + autoware::universe_utils::StopWatch stop_watch; + stop_watch.tic(); + odometry_ptr_ = sub_odometry_.takeData(); pointcloud_ptr_ = sub_pointcloud_.takeData(); object_ptr_ = sub_dynamic_objects_.takeData(); @@ -256,6 +262,11 @@ void SurroundObstacleCheckerNode::onTimer() no_start_reason_diag = makeStopReasonDiag("obstacle", odometry_ptr_->pose.pose); } + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_->publish(processing_time_msg); + pub_stop_reason_->publish(no_start_reason_diag); debug_ptr_->publish(); } diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index f04a3aba07baf..480a937a4a909 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include #include @@ -106,6 +107,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_stop_reason_; rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_processing_time_; // parameter callback result OnSetParametersCallbackHandle::SharedPtr set_param_res_; diff --git a/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml b/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml index 84e7d79079dae..033b20d234fd9 100644 --- a/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml +++ b/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml @@ -2,9 +2,11 @@ ros__parameters: update_rate: 10.0 processing_time_topic_name_list: + - /control/control_validator/debug/processing_time_ms - /control/trajectory_follower/controller_node_exe/lateral/debug/processing_time_ms - /control/trajectory_follower/controller_node_exe/longitudinal/debug/processing_time_ms - /control/trajectory_follower/lane_departure_checker_node/debug/processing_time_ms + - /control/vehicle_cmd_gate/debug/processing_time_ms - /perception/object_recognition/prediction/map_based_prediction/debug/processing_time_ms - /perception/object_recognition/tracking/multi_object_tracker/debug/processing_time_ms - /planning/planning_validator/debug/processing_time_ms @@ -33,5 +35,8 @@ - /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/debug/processing_time_ms - /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/processing_time_ms - /planning/scenario_planning/lane_driving/motion_planning/path_optimizer/debug/processing_time_ms + - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/processing_time_ms + - /planning/scenario_planning/parking/costmap_generator/debug/processing_time_ms + - /planning/scenario_planning/scenario_selector/debug/processing_time_ms - /planning/scenario_planning/velocity_smoother/debug/processing_time_ms - /simulation/shape_estimation/debug/processing_time_ms