@@ -256,18 +256,23 @@ GoalCandidates GoalSearcher::search(
256
256
(transformed_vehicle_footprint.at (vehicle_info_utils::VehicleInfo::FrontLeftIndex) +
257
257
transformed_vehicle_footprint.at (vehicle_info_utils::VehicleInfo::FrontRightIndex)) /
258
258
2.0 ;
259
+ const auto vehicle_rear_midpoint =
260
+ (transformed_vehicle_footprint.at (vehicle_info_utils::VehicleInfo::RearLeftIndex) +
261
+ transformed_vehicle_footprint.at (vehicle_info_utils::VehicleInfo::RearRightIndex)) /
262
+ 2.0 ;
263
+ const auto vehicle_center_point = (vehicle_front_midpoint + vehicle_rear_midpoint) / 2.0 ;
259
264
const auto pull_over_lanelet = lanelet::utils::combineLaneletsShape (pull_over_lanes_);
260
- const auto vehicle_front_pose_for_bound_opt = goal_planner_utils::calcClosestPose (
265
+ const auto vehicle_center_pose_for_bound_opt = goal_planner_utils::calcClosestPose (
261
266
left_side_parking_ ? pull_over_lanelet.leftBound () : pull_over_lanelet.rightBound (),
262
267
autoware::universe_utils::createPoint (
263
- vehicle_front_midpoint .x (), vehicle_front_midpoint .y (), search_pose.position .z ));
264
- if (!vehicle_front_pose_for_bound_opt ) {
268
+ vehicle_center_point .x (), vehicle_center_point .y (), search_pose.position .z ));
269
+ if (!vehicle_center_pose_for_bound_opt ) {
265
270
continue ;
266
271
}
267
- const auto & vehicle_front_pose_for_bound = vehicle_front_pose_for_bound_opt .value ();
272
+ const auto & vehicle_center_pose_for_bound = vehicle_center_pose_for_bound_opt .value ();
268
273
GoalCandidate goal_candidate{};
269
274
goal_candidate.goal_pose = search_pose;
270
- goal_candidate.goal_pose .orientation = vehicle_front_pose_for_bound .orientation ;
275
+ goal_candidate.goal_pose .orientation = vehicle_center_pose_for_bound .orientation ;
271
276
goal_candidate.lateral_offset = dy;
272
277
goal_candidate.id = goal_id;
273
278
goal_id++;
0 commit comments