Skip to content

Commit 38032f1

Browse files
authored
feat(planning_evaluator): add modified goal deviation (autowarefoundation#3053)
* feat(planning_evaluator): add modified goal deviation Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * add abs Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * remove setModifiedGoal Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * use Point and rename func Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * fix func docs Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> * fix and add tests Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> --------- Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 4342bdc commit 38032f1

12 files changed

+268
-52
lines changed

evaluator/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp

+26
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,8 @@ namespace metrics
2626
{
2727
using autoware_auto_planning_msgs::msg::Trajectory;
2828
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
29+
using geometry_msgs::msg::Point;
30+
using geometry_msgs::msg::Pose;
2931

3032
/**
3133
* @brief calculate lateral deviation of the given trajectory from the reference trajectory
@@ -51,6 +53,30 @@ Stat<double> calcYawDeviation(const Trajectory & ref, const Trajectory & traj);
5153
*/
5254
Stat<double> calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj);
5355

56+
/**
57+
* @brief calculate longitudinal deviation of the given ego pose from the modified goal pose
58+
* @param [in] base_pose base pose
59+
* @param [in] target_point target point
60+
* @return calculated statistics
61+
*/
62+
Stat<double> calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point);
63+
64+
/**
65+
* @brief calculate lateral deviation of the given ego pose from the modified goal pose
66+
* @param [in] base_pose base pose
67+
* @param [in] target_point target point
68+
* @return calculated statistics
69+
*/
70+
Stat<double> calcLateralDeviation(const Pose & base_pose, const Point & target_point);
71+
72+
/**
73+
* @brief calculate yaw deviation of the given ego pose from the modified goal pose
74+
* @param [in] base_pose base pose
75+
* @param [in] target_pose target pose
76+
* @return calculated statistics
77+
*/
78+
Stat<double> calcYawDeviation(const Pose & base_pose, const Pose & target_pose);
79+
5480
} // namespace metrics
5581
} // namespace planning_diagnostics
5682

evaluator/planning_evaluator/include/planning_evaluator/metrics/metric.hpp

+15-3
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@ enum class Metric {
4141
stability_frechet,
4242
obstacle_distance,
4343
obstacle_ttc,
44+
modified_goal_longitudinal_deviation,
45+
modified_goal_lateral_deviation,
46+
modified_goal_yaw_deviation,
4447
SIZE,
4548
};
4649

@@ -63,7 +66,10 @@ static const std::unordered_map<std::string, Metric> str_to_metric = {
6366
{"stability_frechet", Metric::stability_frechet},
6467
{"obstacle_distance", Metric::obstacle_distance},
6568
{"obstacle_ttc", Metric::obstacle_ttc},
66-
};
69+
{"modified_goal_longitudinal_deviation", Metric::modified_goal_longitudinal_deviation},
70+
{"modified_goal_lateral_deviation", Metric::modified_goal_lateral_deviation},
71+
{"modified_goal_yaw_deviation", Metric::modified_goal_yaw_deviation}};
72+
6773
static const std::unordered_map<Metric, std::string> metric_to_str = {
6874
{Metric::curvature, "curvature"},
6975
{Metric::point_interval, "point_interval"},
@@ -79,7 +85,10 @@ static const std::unordered_map<Metric, std::string> metric_to_str = {
7985
{Metric::stability, "stability"},
8086
{Metric::stability_frechet, "stability_frechet"},
8187
{Metric::obstacle_distance, "obstacle_distance"},
82-
{Metric::obstacle_ttc, "obstacle_ttc"}};
88+
{Metric::obstacle_ttc, "obstacle_ttc"},
89+
{Metric::modified_goal_longitudinal_deviation, "modified_goal_longitudinal_deviation"},
90+
{Metric::modified_goal_lateral_deviation, "modified_goal_lateral_deviation"},
91+
{Metric::modified_goal_yaw_deviation, "modified_goal_yaw_deviation"}};
8392

8493
// Metrics descriptions
8594
static const std::unordered_map<Metric, std::string> metric_descriptions = {
@@ -97,7 +106,10 @@ static const std::unordered_map<Metric, std::string> metric_descriptions = {
97106
{Metric::stability, "Stability[m]"},
98107
{Metric::stability_frechet, "StabilityFrechet[m]"},
99108
{Metric::obstacle_distance, "Obstacle_distance[m]"},
100-
{Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"}};
109+
{Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"},
110+
{Metric::modified_goal_longitudinal_deviation, "Modified_goal_longitudinal_deviation[m]"},
111+
{Metric::modified_goal_lateral_deviation, "Modified_goal_lateral_deviation[m]"},
112+
{Metric::modified_goal_yaw_deviation, "Modified_goal_yaw_deviation[rad]"}};
101113

102114
namespace details
103115
{

evaluator/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp

+16-2
Original file line numberDiff line numberDiff line change
@@ -14,21 +14,26 @@
1414

1515
#ifndef PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_
1616
#define PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_
17-
1817
#include "planning_evaluator/metrics/metric.hpp"
1918
#include "planning_evaluator/parameters.hpp"
2019
#include "planning_evaluator/stat.hpp"
2120

2221
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
2322
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
2423
#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp"
24+
#include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp"
2525
#include "geometry_msgs/msg/pose.hpp"
2626

27+
#include <optional>
28+
2729
namespace planning_diagnostics
2830
{
2931
using autoware_auto_perception_msgs::msg::PredictedObjects;
3032
using autoware_auto_planning_msgs::msg::Trajectory;
3133
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
34+
using autoware_planning_msgs::msg::PoseWithUuidStamped;
35+
using geometry_msgs::msg::Point;
36+
using geometry_msgs::msg::Pose;
3237

3338
class MetricsCalculator
3439
{
@@ -42,7 +47,9 @@ class MetricsCalculator
4247
* @param [in] metric Metric enum value
4348
* @return string describing the requested metric
4449
*/
45-
Stat<double> calculate(const Metric metric, const Trajectory & traj) const;
50+
std::optional<Stat<double>> calculate(const Metric metric, const Trajectory & traj) const;
51+
std::optional<Stat<double>> calculate(
52+
const Metric metric, const Pose & base_pose, const Pose & target_pose) const;
4653

4754
/**
4855
* @brief set the reference trajectory used to calculate the deviation metrics
@@ -68,6 +75,12 @@ class MetricsCalculator
6875
*/
6976
void setEgoPose(const geometry_msgs::msg::Pose & pose);
7077

78+
/**
79+
* @brief get the ego pose
80+
* @return ego pose
81+
*/
82+
Pose getEgoPose();
83+
7184
private:
7285
/**
7386
* @brief trim a trajectory from the current ego pose to some fixed time or distance
@@ -86,6 +99,7 @@ class MetricsCalculator
8699
Trajectory previous_trajectory_lookahead_;
87100
PredictedObjects dynamic_objects_;
88101
geometry_msgs::msg::Pose ego_pose_;
102+
PoseWithUuidStamped modified_goal_;
89103
}; // class MetricsCalculator
90104

91105
} // namespace planning_diagnostics

evaluator/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp

+20-2
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,9 @@
2424
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
2525
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
2626
#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp"
27+
#include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp"
2728
#include "diagnostic_msgs/msg/diagnostic_array.hpp"
29+
#include "nav_msgs/msg/odometry.hpp"
2830

2931
#include <array>
3032
#include <deque>
@@ -37,8 +39,10 @@ namespace planning_diagnostics
3739
using autoware_auto_perception_msgs::msg::PredictedObjects;
3840
using autoware_auto_planning_msgs::msg::Trajectory;
3941
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
42+
using autoware_planning_msgs::msg::PoseWithUuidStamped;
4043
using diagnostic_msgs::msg::DiagnosticArray;
4144
using diagnostic_msgs::msg::DiagnosticStatus;
45+
using nav_msgs::msg::Odometry;
4246

4347
/**
4448
* @brief Node for planning evaluation
@@ -49,6 +53,12 @@ class PlanningEvaluatorNode : public rclcpp::Node
4953
explicit PlanningEvaluatorNode(const rclcpp::NodeOptions & node_options);
5054
~PlanningEvaluatorNode();
5155

56+
/**
57+
* @brief callback on receiving an odometry
58+
* @param [in] odometry_msg received odometry message
59+
*/
60+
void onOdometry(const Odometry::ConstSharedPtr odometry_msg);
61+
5262
/**
5363
* @brief callback on receiving a trajectory
5464
* @param [in] traj_msg received trajectory message
@@ -68,9 +78,10 @@ class PlanningEvaluatorNode : public rclcpp::Node
6878
void onObjects(const PredictedObjects::ConstSharedPtr objects_msg);
6979

7080
/**
71-
* @brief update the ego pose stored in the MetricsCalculator
81+
* @brief callback on receiving a modified goal
82+
* @param [in] modified_goal_msg received modified goal message
7283
*/
73-
void updateCalculatorEgoPose(const std::string & target_frame);
84+
void onModifiedGoal(const PoseWithUuidStamped::ConstSharedPtr modified_goal_msg);
7485

7586
/**
7687
* @brief publish the given metric statistic
@@ -80,11 +91,15 @@ class PlanningEvaluatorNode : public rclcpp::Node
8091

8192
private:
8293
static bool isFinite(const TrajectoryPoint & p);
94+
void publishModifiedGoalDeviationMetrics();
8395

8496
// ROS
8597
rclcpp::Subscription<Trajectory>::SharedPtr traj_sub_;
8698
rclcpp::Subscription<Trajectory>::SharedPtr ref_sub_;
8799
rclcpp::Subscription<PredictedObjects>::SharedPtr objects_sub_;
100+
rclcpp::Subscription<PoseWithUuidStamped>::SharedPtr modified_goal_sub_;
101+
rclcpp::Subscription<Odometry>::SharedPtr odom_sub_;
102+
88103
rclcpp::Publisher<DiagnosticArray>::SharedPtr metrics_pub_;
89104
std::shared_ptr<tf2_ros::TransformListener> transform_listener_{nullptr};
90105
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
@@ -99,6 +114,9 @@ class PlanningEvaluatorNode : public rclcpp::Node
99114
std::vector<Metric> metrics_;
100115
std::deque<rclcpp::Time> stamps_;
101116
std::array<std::deque<Stat<double>>, static_cast<size_t>(Metric::SIZE)> metric_stats_;
117+
118+
Odometry::ConstSharedPtr ego_state_ptr_;
119+
PoseWithUuidStamped::ConstSharedPtr modified_goal_ptr_;
102120
};
103121
} // namespace planning_diagnostics
104122

evaluator/planning_evaluator/launch/planning_evaluator.launch.xml

+4
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,19 @@
11
<launch>
2+
<arg name="input/odometry" default="/localization/kinematic_state"/>
23
<arg name="input/trajectory" default="/planning/scenario_planning/trajectory"/>
34
<arg name="input/reference_trajectory" default="/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory"/>
45
<arg name="input/objects" default="/perception/object_recognition/objects"/>
6+
<arg name="input/modified_goal" default="/planning/scenario_planning/modified_goal"/>
57

68
<!-- planning evaluator -->
79
<group>
810
<node name="planning_evaluator" exec="planning_evaluator" pkg="planning_evaluator">
911
<param from="$(find-pkg-share planning_evaluator)/param/planning_evaluator.defaults.yaml"/>
12+
<remap from="~/input/odometry" to="$(var input/odometry)"/>
1013
<remap from="~/input/trajectory" to="$(var input/trajectory)"/>
1114
<remap from="~/input/reference_trajectory" to="$(var input/reference_trajectory)"/>
1215
<remap from="~/input/objects" to="$(var input/objects)"/>
16+
<remap from="~/input/modified_goal" to="$(var input/modified_goal)"/>
1317
<remap from="~/metrics" to="/diagnostic/planning_evaluator/metrics"/>
1418
</node>
1519
</group>

evaluator/planning_evaluator/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
<depend>autoware_auto_perception_msgs</depend>
1818
<depend>autoware_auto_planning_msgs</depend>
19+
<depend>autoware_planning_msgs</depend>
1920
<depend>diagnostic_msgs</depend>
2021
<depend>eigen</depend>
2122
<depend>geometry_msgs</depend>

evaluator/planning_evaluator/param/planning_evaluator.defaults.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,9 @@
1919
- stability_frechet
2020
- obstacle_distance
2121
- obstacle_ttc
22+
- modified_goal_longitudinal_deviation
23+
- modified_goal_lateral_deviation
24+
- modified_goal_yaw_deviation
2225

2326
trajectory:
2427
min_point_dist_m: 0.1 # [m] minimum distance between two successive points to use for angle calculation

evaluator/planning_evaluator/src/metrics/deviation_metrics.cpp

+20
Original file line numberDiff line numberDiff line change
@@ -77,5 +77,25 @@ Stat<double> calcVelocityDeviation(const Trajectory & ref, const Trajectory & tr
7777
return stat;
7878
}
7979

80+
Stat<double> calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point)
81+
{
82+
Stat<double> stat;
83+
stat.add(std::abs(tier4_autoware_utils::calcLongitudinalDeviation(base_pose, target_point)));
84+
return stat;
85+
}
86+
87+
Stat<double> calcLateralDeviation(const Pose & base_pose, const Point & target_point)
88+
{
89+
Stat<double> stat;
90+
stat.add(std::abs(tier4_autoware_utils::calcLateralDeviation(base_pose, target_point)));
91+
return stat;
92+
}
93+
94+
Stat<double> calcYawDeviation(const Pose & base_pose, const Pose & target_pose)
95+
{
96+
Stat<double> stat;
97+
stat.add(std::abs(tier4_autoware_utils::calcYawDeviation(base_pose, target_pose)));
98+
return stat;
99+
}
80100
} // namespace metrics
81101
} // namespace planning_diagnostics

evaluator/planning_evaluator/src/metrics_calculator.cpp

+22-5
Original file line numberDiff line numberDiff line change
@@ -23,9 +23,10 @@
2323

2424
namespace planning_diagnostics
2525
{
26-
Stat<double> MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const
26+
std::optional<Stat<double>> MetricsCalculator::calculate(
27+
const Metric metric, const Trajectory & traj) const
2728
{
28-
// Functions to calculate metrics
29+
// Functions to calculate trajectory metrics
2930
switch (metric) {
3031
case Metric::curvature:
3132
return metrics::calcTrajectoryCurvature(traj);
@@ -70,9 +71,23 @@ Stat<double> MetricsCalculator::calculate(const Metric metric, const Trajectory
7071
case Metric::obstacle_ttc:
7172
return metrics::calcTimeToCollision(dynamic_objects_, traj, parameters.obstacle.dist_thr_m);
7273
default:
73-
throw std::runtime_error(
74-
"[MetricsCalculator][calculate()] unknown Metric " +
75-
std::to_string(static_cast<int>(metric)));
74+
return {};
75+
}
76+
}
77+
78+
std::optional<Stat<double>> MetricsCalculator::calculate(
79+
const Metric metric, const Pose & base_pose, const Pose & target_pose) const
80+
{
81+
// Functions to calculate pose metrics
82+
switch (metric) {
83+
case Metric::modified_goal_longitudinal_deviation:
84+
return metrics::calcLongitudinalDeviation(base_pose, target_pose.position);
85+
case Metric::modified_goal_lateral_deviation:
86+
return metrics::calcLateralDeviation(base_pose, target_pose.position);
87+
case Metric::modified_goal_yaw_deviation:
88+
return metrics::calcYawDeviation(base_pose, target_pose);
89+
default:
90+
return {};
7691
}
7792
}
7893

@@ -93,6 +108,8 @@ void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects)
93108

94109
void MetricsCalculator::setEgoPose(const geometry_msgs::msg::Pose & pose) { ego_pose_ = pose; }
95110

111+
Pose MetricsCalculator::getEgoPose() { return ego_pose_; }
112+
96113
Trajectory MetricsCalculator::getLookaheadTrajectory(
97114
const Trajectory & traj, const double max_dist_m, const double max_time_s) const
98115
{

evaluator/planning_evaluator/src/motion_evaluator_node.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,9 @@ MotionEvaluatorNode::~MotionEvaluatorNode()
5555
f << std::endl;
5656
for (Metric metric : metrics_) {
5757
const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_);
58-
f /* << std::setw(3 * column_width) */ << stat << " ";
58+
if (stat) {
59+
f /* << std::setw(3 * column_width) */ << *stat << " ";
60+
}
5961
}
6062
f.close();
6163
}

0 commit comments

Comments
 (0)