diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index adea18c726ced..079682502fa2c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1486,7 +1486,7 @@ void fillObjectEnvelopePolygon( calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); if (error_eclipse_long_radius > object_parameter.th_error_eclipse_long_radius) { - if (error_eclipse_long_radius < object_data.error_eclipse_max) { + if (error_eclipse_long_radius < same_id_obj->error_eclipse_max) { object_data.error_eclipse_max = error_eclipse_long_radius; object_data.envelope_poly = one_shot_envelope_poly; return;