From 8ae14aab173c570947b1caa5fa96d840991dbd23 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 7 Feb 2025 13:50:01 +0900 Subject: [PATCH] fix(motion_velocity_planner_common): fix the calc_possible_min_dist_from_obj_to_traj_poly calculation (#10059) * fix(motion_velocity_planner_common): fix the calc_possible_min_dist_from_obj_to_traj_poly calculation Signed-off-by: Takayuki Murooka * update maintainer Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../package.xml | 2 ++ .../src/utils.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml index 8c33cfc862271..214e69f4122a2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml @@ -7,6 +7,8 @@ Maxime Clement Alqudah Mohammad + Takayuki Murooka + Yuki Takagi Apache License 2.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/utils.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/utils.cpp index de86f64fa7965..cf1e888116616 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/utils.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/utils.cpp @@ -169,7 +169,7 @@ double calc_possible_min_dist_from_obj_to_traj_poly( const double object_possible_max_dist = calc_object_possible_max_dist_from_center(object->predicted_object.shape); const double possible_min_dist_to_traj_poly = - std::abs(object->get_dist_to_traj_lateral(traj_points)) - vehicle_info.vehicle_width_m - + std::abs(object->get_dist_to_traj_lateral(traj_points)) - vehicle_info.vehicle_width_m / 2.0 - object_possible_max_dist; return possible_min_dist_to_traj_poly; }