Skip to content

Commit

Permalink
feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulat…
Browse files Browse the repository at this point in the history
…or_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (#9180)

* first commit

Signed-off-by: xtk8532704 <[email protected]>

* fix building errs.

Signed-off-by: xtk8532704 <[email protected]>

* change diagnostic messages to metric messages for publishing decision.

Signed-off-by: xtk8532704 <[email protected]>

* fix bug about motion_velocity_planner

Signed-off-by: xtk8532704 <[email protected]>

* change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner.

Signed-off-by: xtk8532704 <[email protected]>

* tmp save for planning_evaluator

Signed-off-by: xtk8532704 <[email protected]>

* change the topic to which metrics published to.

Signed-off-by: xtk8532704 <[email protected]>

* fix typo.

Signed-off-by: xtk8532704 <[email protected]>

* remove unnesessary publishing of metrics.

Signed-off-by: xtk8532704 <[email protected]>

* mke planning_evaluator publish msg of MetricArray instead of Diags.

Signed-off-by: xtk8532704 <[email protected]>

* update aeb with metric type for decision.

Signed-off-by: xtk8532704 <[email protected]>

* fix some bug

Signed-off-by: xtk8532704 <[email protected]>

* remove autoware_evaluator_utils package.

Signed-off-by: xtk8532704 <[email protected]>

* remove diagnostic_msgs dependency of planning_evaluator

Signed-off-by: xtk8532704 <[email protected]>

* use metric_msgs for autoware_processing_time_checker.

Signed-off-by: xtk8532704 <[email protected]>

* rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs.

Signed-off-by: xtk8532704 <[email protected]>

* pre-commit and fix typo

Signed-off-by: xtk8532704 <[email protected]>

* publish metrics even if there is no metric in the MetricArray.

Signed-off-by: xtk8532704 <[email protected]>

* modify the metric name of processing_time.

Signed-off-by: xtk8532704 <[email protected]>

* update unit test for test_planning/control_evaluator

Signed-off-by: xtk8532704 <[email protected]>

* manual pre-commit

Signed-off-by: xtk8532704 <[email protected]>

---------

Signed-off-by: xtk8532704 <[email protected]>
  • Loading branch information
xtk8532704 authored Nov 12, 2024
1 parent 8652963 commit 5cd47a7
Show file tree
Hide file tree
Showing 51 changed files with 687 additions and 1,005 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ control/predicted_path_checker/** [email protected]
evaluator/autoware_control_evaluator/** [email protected] [email protected] [email protected] [email protected]
evaluator/autoware_evaluator_utils/** [email protected] [email protected]
evaluator/autoware_planning_evaluator/** [email protected] [email protected]
evaluator/diagnostic_converter/** [email protected] [email protected] [email protected]
evaluator/scenario_simulator_v2_adapter/** [email protected] [email protected] [email protected]
evaluator/kinematic_evaluator/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
evaluator/localization_evaluator/** [email protected] [email protected]
evaluator/perception_online_evaluator/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

Expand Down Expand Up @@ -77,6 +79,8 @@ using Vector3 = geometry_msgs::msg::Vector3;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using colorTuple = std::tuple<double, double, double, double>;
using Metric = tier4_metric_msgs::msg::Metric;
using MetricArray = tier4_metric_msgs::msg::MetricArray;

/**
* @brief Struct to store object data
Expand Down Expand Up @@ -345,6 +349,7 @@ class AEB : public rclcpp::Node
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
debug_processing_time_detail_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr debug_rss_distance_publisher_;
rclcpp::Publisher<MetricArray>::SharedPtr metrics_pub_;
// timer
rclcpp::TimerBase::SharedPtr timer_;
mutable std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_{nullptr};
Expand Down
1 change: 1 addition & 0 deletions control/autoware_autonomous_emergency_braking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_metric_msgs</depend>
<depend>visualization_msgs</depend>

<export>
Expand Down
13 changes: 13 additions & 0 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
virtual_wall_publisher_ = this->create_publisher<MarkerArray>("~/virtual_wall", 1);
debug_rss_distance_publisher_ =
this->create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/debug/rss_distance", 1);
metrics_pub_ = this->create_publisher<MetricArray>("~/metrics", 1);
}
// Diagnostics
{
Expand Down Expand Up @@ -400,6 +401,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
{
MarkerArray debug_markers;
MarkerArray virtual_wall_marker;
auto metrics = MetricArray();
checkCollision(debug_markers);

if (!collision_data_keeper_.checkCollisionExpired()) {
Expand All @@ -416,6 +418,14 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
}
}
addVirtualStopWallMarker(virtual_wall_marker);

{
auto metric = Metric();
metric.name = "decision";
metric.value = "brake";
metrics.metric_array.push_back(metric);
}

} else {
const std::string error_msg = "[AEB]: No Collision";
const auto diag_level = DiagnosticStatus::OK;
Expand All @@ -425,6 +435,9 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
// publish debug markers
debug_marker_publisher_->publish(debug_markers);
virtual_wall_publisher_->publish(virtual_wall_marker);
// publish metrics
metrics.stamp = get_clock()->now();
metrics_pub_->publish(metrics);
}

bool AEB::checkCollision(MarkerArray & debug_markers)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,27 +23,26 @@

#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>

#include <deque>
#include <optional>
#include <string>
#include <utility>
#include <vector>

namespace control_diagnostics
{

using autoware_planning_msgs::msg::Trajectory;
using diagnostic_msgs::msg::DiagnosticArray;
using diagnostic_msgs::msg::DiagnosticStatus;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin;
using autoware_planning_msgs::msg::LaneletRoute;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using MetricMsg = tier4_metric_msgs::msg::Metric;
using MetricArrayMsg = tier4_metric_msgs::msg::MetricArray;

/**
* @brief Node for control evaluation
Expand All @@ -52,28 +51,19 @@ class ControlEvaluatorNode : public rclcpp::Node
{
public:
explicit ControlEvaluatorNode(const rclcpp::NodeOptions & node_options);
DiagnosticStatus generateLateralDeviationDiagnosticStatus(
const Trajectory & traj, const Point & ego_point);
DiagnosticStatus generateYawDeviationDiagnosticStatus(
const Trajectory & traj, const Pose & ego_pose);
DiagnosticStatus generateGoalLongitudinalDeviationDiagnosticStatus(const Pose & ego_pose);
DiagnosticStatus generateGoalLateralDeviationDiagnosticStatus(const Pose & ego_pose);
DiagnosticStatus generateGoalYawDeviationDiagnosticStatus(const Pose & ego_pose);

DiagnosticStatus generateAEBDiagnosticStatus(const DiagnosticStatus & diag);
DiagnosticStatus generateLaneletDiagnosticStatus(const Pose & ego_pose) const;
DiagnosticStatus generateKinematicStateDiagnosticStatus(
void AddLateralDeviationMetricMsg(const Trajectory & traj, const Point & ego_point);
void AddYawDeviationMetricMsg(const Trajectory & traj, const Pose & ego_pose);
void AddGoalLongitudinalDeviationMetricMsg(const Pose & ego_pose);
void AddGoalLateralDeviationMetricMsg(const Pose & ego_pose);
void AddGoalYawDeviationMetricMsg(const Pose & ego_pose);

void AddLaneletMetricMsg(const Pose & ego_pose);
void AddKinematicStateMetricMsg(
const Odometry & odom, const AccelWithCovarianceStamped & accel_stamped);

void onDiagnostics(const DiagnosticArray::ConstSharedPtr diag_msg);
void onTimer();

private:
// 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<DiagnosticArray>::SharedPtr control_diag_sub_;

autoware::universe_utils::InterProcessPollingSubscriber<Odometry> odometry_sub_{
this, "~/input/odometry"};
autoware::universe_utils::InterProcessPollingSubscriber<AccelWithCovarianceStamped> accel_sub_{
Expand All @@ -87,7 +77,7 @@ class ControlEvaluatorNode : public rclcpp::Node
LaneletMapBin, autoware::universe_utils::polling_policy::Newest>
vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()};

rclcpp::Publisher<DiagnosticArray>::SharedPtr metrics_pub_;
rclcpp::Publisher<MetricArrayMsg>::SharedPtr metrics_pub_;

// update Route Handler
void getRouteData();
Expand All @@ -96,10 +86,7 @@ class ControlEvaluatorNode : public rclcpp::Node
// Metrics
std::deque<rclcpp::Time> stamps_;

// queue for diagnostics and time stamp
std::deque<std::pair<DiagnosticStatus, rclcpp::Time>> diag_queue_;
const std::vector<std::string> target_functions_ = {"autonomous_emergency_braking"};

MetricArrayMsg metrics_msg_;
autoware::route_handler::RouteHandler route_handler_;
rclcpp::TimerBase::SharedPtr timer_;
std::optional<AccelWithCovarianceStamped> prev_acc_stamped_{std::nullopt};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
<remap from="~/input/odometry" to="$(var input/odometry)"/>
<remap from="~/input/acceleration" to="$(var input/acceleration)"/>
<remap from="~/input/trajectory" to="$(var input/trajectory)"/>
<remap from="~/metrics" to="/control/control_evaluator/metrics"/>
<remap from="~/input/vector_map" to="$(var map_topic_name)"/>
<remap from="~/input/route" to="$(var route_topic_name)"/>
</node>
Expand Down
3 changes: 1 addition & 2 deletions evaluator/autoware_control_evaluator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,19 +16,18 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_evaluator_utils</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_test_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>diagnostic_msgs</depend>
<depend>nav_msgs</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tier4_metric_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Loading

0 comments on commit 5cd47a7

Please sign in to comment.