Skip to content

Commit 317c998

Browse files
authored
feat(goal_planner): align vehicle center to be parallel to lane boundary (autowarefoundation#10118)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent c6665a7 commit 317c998

File tree

1 file changed

+10
-5
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src

1 file changed

+10
-5
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

+10-5
Original file line numberDiff line numberDiff line change
@@ -256,18 +256,23 @@ GoalCandidates GoalSearcher::search(
256256
(transformed_vehicle_footprint.at(vehicle_info_utils::VehicleInfo::FrontLeftIndex) +
257257
transformed_vehicle_footprint.at(vehicle_info_utils::VehicleInfo::FrontRightIndex)) /
258258
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;
259264
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(
261266
left_side_parking_ ? pull_over_lanelet.leftBound() : pull_over_lanelet.rightBound(),
262267
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) {
265270
continue;
266271
}
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();
268273
GoalCandidate goal_candidate{};
269274
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;
271276
goal_candidate.lateral_offset = dy;
272277
goal_candidate.id = goal_id;
273278
goal_id++;

0 commit comments

Comments
 (0)