diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index 85ae411311612..d07ed22fc12dd 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -16,8 +16,8 @@ #include "autoware/evaluator_utils/evaluator_utils.hpp" -#include -#include +#include +#include #include #include diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp index e63f24396bd6f..0121425c15d1d 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp @@ -21,25 +21,19 @@ #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include -#include - #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "diagnostic_msgs/msg/diagnostic_array.hpp" -#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include -#include #include #include #include #include -#include #include + namespace planning_diagnostics { using autoware_perception_msgs::msg::PredictedObjects; @@ -49,9 +43,6 @@ using autoware_planning_msgs::msg::TrajectoryPoint; using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; using nav_msgs::msg::Odometry; -using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; -using autoware_planning_msgs::msg::LaneletRoute; -using geometry_msgs::msg::AccelWithCovarianceStamped; /** * @brief Node for planning evaluation */ @@ -91,54 +82,15 @@ class PlanningEvaluatorNode : public rclcpp::Node */ void onModifiedGoal(const PoseWithUuidStamped::ConstSharedPtr modified_goal_msg); - /** - * @brief obtain diagnostics information - */ - void onDiagnostics(const DiagnosticArray::ConstSharedPtr diag_msg); - /** * @brief publish the given metric statistic */ DiagnosticStatus generateDiagnosticStatus( const Metric & metric, const Stat & metric_stat) const; - /** - * @brief publish current ego lane info - */ - DiagnosticStatus generateDiagnosticEvaluationStatus(const DiagnosticStatus & diag); - - /** - * @brief publish current ego lane info - */ - DiagnosticStatus generateLaneletDiagnosticStatus(const Odometry::ConstSharedPtr ego_state_ptr); - - /** - * @brief publish current ego kinematic state - */ - DiagnosticStatus generateKinematicStateDiagnosticStatus( - const AccelWithCovarianceStamped & accel_stamped, const Odometry::ConstSharedPtr ego_state_ptr); - private: static bool isFinite(const TrajectoryPoint & p); - - /** - * @brief update route handler data - */ - void getRouteData(); - - /** - * @brief fetch data and publish diagnostics - */ - void onTimer(); - - /** - * @brief fetch topic data - */ - void fetchData(); - // The diagnostics cycle is faster than timer, and each node publishes diagnostic separately. - // takeData() in onTimer() with a polling subscriber will miss a topic, so save all topics with - // onDiagnostics(). - rclcpp::Subscription::SharedPtr planning_diag_sub_; + void publishModifiedGoalDeviationMetrics(); // ROS rclcpp::Subscription::SharedPtr traj_sub_; @@ -146,17 +98,10 @@ class PlanningEvaluatorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr objects_sub_; rclcpp::Subscription::SharedPtr modified_goal_sub_; rclcpp::Subscription::SharedPtr odom_sub_; - autoware::universe_utils::InterProcessPollingSubscriber route_subscriber_{ - this, "~/input/route", rclcpp::QoS{1}.transient_local()}; - autoware::universe_utils::InterProcessPollingSubscriber vector_map_subscriber_{ - this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; - autoware::universe_utils::InterProcessPollingSubscriber accel_sub_{ - this, "~/input/acceleration"}; rclcpp::Publisher::SharedPtr metrics_pub_; std::shared_ptr transform_listener_{nullptr}; std::unique_ptr tf_buffer_; - autoware::route_handler::RouteHandler route_handler_; // Parameters std::string output_file_str_; @@ -169,11 +114,8 @@ class PlanningEvaluatorNode : public rclcpp::Node std::deque stamps_; std::array>, static_cast(Metric::SIZE)> metric_stats_; - rclcpp::TimerBase::SharedPtr timer_; - // queue for diagnostics and time stamp - std::deque> diag_queue_; - const std::vector target_functions_ = {"obstacle_cruise_planner"}; - std::optional prev_acc_stamped_{std::nullopt}; + Odometry::ConstSharedPtr ego_state_ptr_; + PoseWithUuidStamped::ConstSharedPtr modified_goal_ptr_; }; } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml b/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml index ec509993afc18..b36e276c06944 100644 --- a/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml +++ b/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml @@ -1,27 +1,19 @@ - - - - - - - - diff --git a/evaluator/autoware_planning_evaluator/package.xml b/evaluator/autoware_planning_evaluator/package.xml index eb3161e0afb35..5bd500f200eac 100644 --- a/evaluator/autoware_planning_evaluator/package.xml +++ b/evaluator/autoware_planning_evaluator/package.xml @@ -13,11 +13,9 @@ ament_cmake_auto autoware_cmake - autoware_evaluator_utils autoware_motion_utils autoware_perception_msgs autoware_planning_msgs - autoware_route_handler autoware_universe_utils diagnostic_msgs eigen diff --git a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp index 669afdd7229b0..e17cfd98b27da 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp @@ -30,8 +30,9 @@ size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, cons const TrajectoryPoint & curr_p = traj.points.at(curr_id); size_t target_id = curr_id; + double current_distance = 0.0; for (size_t traj_id = curr_id + 1; traj_id < traj.points.size(); ++traj_id) { - double current_distance = calcDistance2d(traj.points.at(traj_id), curr_p); + current_distance = calcDistance2d(traj.points.at(traj_id), curr_p); if (current_distance >= distance) { target_id = traj_id; break; diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index e87d8e124f490..103e14c73f26d 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -14,16 +14,8 @@ #include "autoware/planning_evaluator/planning_evaluator_node.hpp" -#include "autoware/evaluator_utils/evaluator_utils.hpp" - -#include -#include - -#include - #include "boost/lexical_cast.hpp" -#include #include #include #include @@ -71,9 +63,6 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op output_file_str_ = declare_parameter("output_file"); ego_frame_str_ = declare_parameter("ego_frame"); - planning_diag_sub_ = create_subscription( - "~/input/diagnostics", 1, std::bind(&PlanningEvaluatorNode::onDiagnostics, this, _1)); - // List of metrics to calculate and publish metrics_pub_ = create_publisher("~/metrics", 1); for (const std::string & selected_metric : @@ -116,121 +105,6 @@ PlanningEvaluatorNode::~PlanningEvaluatorNode() } } -void PlanningEvaluatorNode::onDiagnostics(const DiagnosticArray::ConstSharedPtr diag_msg) -{ - // add target diagnostics to the queue and remove old ones - for (const auto & function : target_functions_) { - autoware::evaluator_utils::updateDiagnosticQueue(*diag_msg, function, now(), diag_queue_); - } -} - -DiagnosticStatus PlanningEvaluatorNode::generateDiagnosticEvaluationStatus( - const DiagnosticStatus & diag) -{ - DiagnosticStatus status; - status.name = diag.name; - - const auto it = std::find_if(diag.values.begin(), diag.values.end(), [](const auto & key_value) { - return key_value.key.find("decision") != std::string::npos; - }); - const bool found = it != diag.values.end(); - status.level = (found) ? status.OK : status.ERROR; - status.values.push_back((found) ? *it : diagnostic_msgs::msg::KeyValue{}); - return status; -} - -void PlanningEvaluatorNode::getRouteData() -{ - // route - { - const auto msg = route_subscriber_.takeNewData(); - if (msg) { - if (msg->segments.empty()) { - RCLCPP_ERROR(get_logger(), "input route is empty. ignored"); - } else { - route_handler_.setRoute(*msg); - } - } - } - - // map - { - const auto msg = vector_map_subscriber_.takeNewData(); - if (msg) { - route_handler_.setMap(*msg); - } - } -} - -DiagnosticStatus PlanningEvaluatorNode::generateLaneletDiagnosticStatus( - const Odometry::ConstSharedPtr ego_state_ptr) -{ - const auto & ego_pose = ego_state_ptr->pose.pose; - const auto current_lanelets = [&]() { - lanelet::ConstLanelet closest_route_lanelet; - route_handler_.getClosestLaneletWithinRoute(ego_pose, &closest_route_lanelet); - const auto shoulder_lanelets = route_handler_.getShoulderLaneletsAtPose(ego_pose); - lanelet::ConstLanelets closest_lanelets{closest_route_lanelet}; - closest_lanelets.insert( - closest_lanelets.end(), shoulder_lanelets.begin(), shoulder_lanelets.end()); - return closest_lanelets; - }(); - const auto arc_coordinates = lanelet::utils::getArcCoordinates(current_lanelets, ego_pose); - lanelet::ConstLanelet current_lane; - lanelet::utils::query::getClosestLanelet(current_lanelets, ego_pose, ¤t_lane); - - DiagnosticStatus status; - status.name = "ego_lane_info"; - status.level = status.OK; - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "lane_id"; - key_value.value = std::to_string(current_lane.id()); - status.values.push_back(key_value); - key_value.key = "s"; - key_value.value = std::to_string(arc_coordinates.length); - status.values.push_back(key_value); - key_value.key = "t"; - key_value.value = std::to_string(arc_coordinates.distance); - status.values.push_back(key_value); - return status; -} - -DiagnosticStatus PlanningEvaluatorNode::generateKinematicStateDiagnosticStatus( - const AccelWithCovarianceStamped & accel_stamped, const Odometry::ConstSharedPtr ego_state_ptr) -{ - DiagnosticStatus status; - status.name = "kinematic_state"; - status.level = status.OK; - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "vel"; - key_value.value = std::to_string(ego_state_ptr->twist.twist.linear.x); - status.values.push_back(key_value); - key_value.key = "acc"; - const auto & acc = accel_stamped.accel.accel.linear.x; - key_value.value = std::to_string(acc); - status.values.push_back(key_value); - key_value.key = "jerk"; - const auto jerk = [&]() { - if (!prev_acc_stamped_.has_value()) { - prev_acc_stamped_ = accel_stamped; - return 0.0; - } - const auto t = static_cast(accel_stamped.header.stamp.sec) + - static_cast(accel_stamped.header.stamp.nanosec) * 1e-9; - const auto prev_t = static_cast(prev_acc_stamped_.value().header.stamp.sec) + - static_cast(prev_acc_stamped_.value().header.stamp.nanosec) * 1e-9; - const auto dt = t - prev_t; - if (dt < std::numeric_limits::epsilon()) return 0.0; - - const auto prev_acc = prev_acc_stamped_.value().accel.accel.linear.x; - prev_acc_stamped_ = accel_stamped; - return (acc - prev_acc) / dt; - }(); - key_value.value = std::to_string(jerk); - status.values.push_back(key_value); - return status; -} - DiagnosticStatus PlanningEvaluatorNode::generateDiagnosticStatus( const Metric & metric, const Stat & metric_stat) const { @@ -252,55 +126,7 @@ DiagnosticStatus PlanningEvaluatorNode::generateDiagnosticStatus( void PlanningEvaluatorNode::onTrajectory(const Trajectory::ConstSharedPtr traj_msg) { - metrics_msg_.header.stamp = now(); - - const auto ego_state_ptr = odometry_sub_.takeData(); - onOdometry(ego_state_ptr); - { - const auto objects_msg = objects_sub_.takeData(); - onObjects(objects_msg); - } - - { - const auto ref_traj_msg = ref_sub_.takeData(); - onReferenceTrajectory(ref_traj_msg); - } - - { - const auto traj_msg = traj_sub_.takeData(); - onTrajectory(traj_msg, ego_state_ptr); - } - { - const auto modified_goal_msg = modified_goal_sub_.takeData(); - onModifiedGoal(modified_goal_msg, ego_state_ptr); - } - - { - // generate decision diagnostics from input diagnostics - for (const auto & function : target_functions_) { - const auto it = std::find_if( - diag_queue_.begin(), diag_queue_.end(), - [&function](const std::pair & p) { - return p.first.name.find(function) != std::string::npos; - }); - if (it == diag_queue_.end()) { - continue; - } - // generate each decision diagnostics - metrics_msg_.status.push_back(generateDiagnosticEvaluationStatus(it->first)); - } - } - - if (!metrics_msg_.status.empty()) { - metrics_pub_->publish(metrics_msg_); - } - metrics_msg_ = DiagnosticArray{}; -} - -void PlanningEvaluatorNode::onTrajectory( - const Trajectory::ConstSharedPtr traj_msg, const Odometry::ConstSharedPtr ego_state_ptr) -{ - if (!ego_state_ptr || !traj_msg) { + if (!ego_state_ptr_) { return; } @@ -346,25 +172,6 @@ void PlanningEvaluatorNode::onOdometry(const Odometry::ConstSharedPtr odometry_m { ego_state_ptr_ = odometry_msg; metrics_calculator_.setEgoPose(odometry_msg->pose.pose); - { - DiagnosticArray metrics_msg; - metrics_msg.header.stamp = now(); - - getRouteData(); - if (route_handler_.isHandlerReady() && ego_state_ptr_) { - metrics_msg.status.push_back(generateLaneletDiagnosticStatus()); - } - - const auto acc = accel_sub_.takeData(); - - if (acc && ego_state_ptr_) { - metrics_msg.status.push_back(generateKinematicStateDiagnosticStatus(*acc)); - } - - if (!metrics_msg.status.empty()) { - metrics_pub_->publish(metrics_msg); - } - } if (modified_goal_ptr_) { publishModifiedGoalDeviationMetrics();