Skip to content

Commit 35ecc19

Browse files
feat(control_evaluator): add goal accuracy longitudinal, lateral, yaw (#9155)
* feat(control_evaluator): add goal accuracy longitudinal, lateral, yaw Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * style(pre-commit): autofix * fix: content of kosuke55-san comments Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * fix: variable name Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> * fix: variable name Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> --------- Signed-off-by: Kasunori-Nakajima <kazunori.nakajima@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent f501625 commit 35ecc19

File tree

4 files changed

+93
-0
lines changed

4 files changed

+93
-0
lines changed

evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,9 @@ class ControlEvaluatorNode : public rclcpp::Node
5656
const Trajectory & traj, const Point & ego_point);
5757
DiagnosticStatus generateYawDeviationDiagnosticStatus(
5858
const Trajectory & traj, const Pose & ego_pose);
59+
DiagnosticStatus generateGoalLongitudinalDeviationDiagnosticStatus(const Pose & ego_pose);
60+
DiagnosticStatus generateGoalLateralDeviationDiagnosticStatus(const Pose & ego_pose);
61+
DiagnosticStatus generateGoalYawDeviationDiagnosticStatus(const Pose & ego_pose);
5962

6063
DiagnosticStatus generateAEBDiagnosticStatus(const DiagnosticStatus & diag);
6164
DiagnosticStatus generateLaneletDiagnosticStatus(const Pose & ego_pose) const;

evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/deviation_metrics.hpp

+24
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,30 @@ double calcLateralDeviation(const Trajectory & traj, const Point & point);
4242
*/
4343
double calcYawDeviation(const Trajectory & traj, const Pose & pose);
4444

45+
/**
46+
* @brief calculate longitudinal deviation from target_point to base_pose
47+
* @param [in] pose input base_pose
48+
* @param [in] point input target_point
49+
* @return longitudinal deviation from base_pose to target_point
50+
*/
51+
double calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point);
52+
53+
/**
54+
* @brief calculate lateral deviation from target_point to base_pose
55+
* @param [in] pose input base_pose
56+
* @param [in] point input target_point
57+
* @return lateral deviation from base_pose to target_point
58+
*/
59+
double calcLateralDeviation(const Pose & base_pose, const Point & target_point);
60+
61+
/**
62+
* @brief calculate yaw deviation from base_pose to target_pose
63+
* @param [in] pose input base_pose
64+
* @param [in] pose input target_pose
65+
* @return yaw deviation from base_pose to target_pose
66+
*/
67+
double calcYawDeviation(const Pose & base_pose, const Pose & target_pose);
68+
4569
} // namespace metrics
4670
} // namespace control_diagnostics
4771

evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp

+51
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,53 @@ DiagnosticStatus ControlEvaluatorNode::generateYawDeviationDiagnosticStatus(
186186
return status;
187187
}
188188

189+
DiagnosticStatus ControlEvaluatorNode::generateGoalLongitudinalDeviationDiagnosticStatus(
190+
const Pose & ego_pose)
191+
{
192+
DiagnosticStatus status;
193+
const double longitudinal_deviation =
194+
metrics::calcLongitudinalDeviation(route_handler_.getGoalPose(), ego_pose.position);
195+
196+
status.level = status.OK;
197+
status.name = "goal_longitudinal_deviation";
198+
diagnostic_msgs::msg::KeyValue key_value;
199+
key_value.key = "metrics_value";
200+
key_value.value = std::to_string(longitudinal_deviation);
201+
status.values.push_back(key_value);
202+
return status;
203+
}
204+
205+
DiagnosticStatus ControlEvaluatorNode::generateGoalLateralDeviationDiagnosticStatus(
206+
const Pose & ego_pose)
207+
{
208+
DiagnosticStatus status;
209+
const double lateral_deviation =
210+
metrics::calcLateralDeviation(route_handler_.getGoalPose(), ego_pose.position);
211+
212+
status.level = status.OK;
213+
status.name = "goal_lateral_deviation";
214+
diagnostic_msgs::msg::KeyValue key_value;
215+
key_value.key = "metrics_value";
216+
key_value.value = std::to_string(lateral_deviation);
217+
status.values.push_back(key_value);
218+
return status;
219+
}
220+
221+
DiagnosticStatus ControlEvaluatorNode::generateGoalYawDeviationDiagnosticStatus(
222+
const Pose & ego_pose)
223+
{
224+
DiagnosticStatus status;
225+
const double yaw_deviation = metrics::calcYawDeviation(route_handler_.getGoalPose(), ego_pose);
226+
227+
status.level = status.OK;
228+
status.name = "goal_yaw_deviation";
229+
diagnostic_msgs::msg::KeyValue key_value;
230+
key_value.key = "metrics_value";
231+
key_value.value = std::to_string(yaw_deviation);
232+
status.values.push_back(key_value);
233+
return status;
234+
}
235+
189236
void ControlEvaluatorNode::onTimer()
190237
{
191238
DiagnosticArray metrics_msg;
@@ -222,6 +269,10 @@ void ControlEvaluatorNode::onTimer()
222269
if (odom && route_handler_.isHandlerReady()) {
223270
const Pose ego_pose = odom->pose.pose;
224271
metrics_msg.status.push_back(generateLaneletDiagnosticStatus(ego_pose));
272+
273+
metrics_msg.status.push_back(generateGoalLongitudinalDeviationDiagnosticStatus(ego_pose));
274+
metrics_msg.status.push_back(generateGoalLateralDeviationDiagnosticStatus(ego_pose));
275+
metrics_msg.status.push_back(generateGoalYawDeviationDiagnosticStatus(ego_pose));
225276
}
226277

227278
if (odom && acc) {

evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp

+15
Original file line numberDiff line numberDiff line change
@@ -38,5 +38,20 @@ double calcYawDeviation(const Trajectory & traj, const Pose & pose)
3838
autoware::universe_utils::calcYawDeviation(traj.points[nearest_index].pose, pose));
3939
}
4040

41+
double calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point)
42+
{
43+
return std::abs(autoware::universe_utils::calcLongitudinalDeviation(base_pose, target_point));
44+
}
45+
46+
double calcLateralDeviation(const Pose & base_pose, const Point & target_point)
47+
{
48+
return std::abs(autoware::universe_utils::calcLateralDeviation(base_pose, target_point));
49+
}
50+
51+
double calcYawDeviation(const Pose & base_pose, const Pose & target_pose)
52+
{
53+
return std::abs(autoware::universe_utils::calcYawDeviation(base_pose, target_pose));
54+
}
55+
4156
} // namespace metrics
4257
} // namespace control_diagnostics

0 commit comments

Comments
 (0)