Skip to content

Commit 0aa1c46

Browse files
fix(autoware_behavior_path_start_planner_module): update parameter name for geometric pull out max steer angle
Signed-off-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
1 parent 6aabfaf commit 0aa1c46

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,8 @@ std::optional<PullOutPath> GeometricPullOut::plan(
6666
// check if the ego is at left or right side of road lane center
6767
const bool left_side_start = 0 < getArcCoordinates(road_lanes, start_pose).distance;
6868
const double max_steer_angle =
69-
vehicle_info_.max_steer_angle_rad * parallel_parking_parameters_.max_steer_angle_margin_scale;
69+
vehicle_info_.max_steer_angle_rad *
70+
parallel_parking_parameters_.geometric_pull_out_max_steer_angle_margin_scale;
7071

7172
planner_.setTurningRadius(planner_data->parameters, max_steer_angle);
7273
planner_.setPlannerData(planner_data);

0 commit comments

Comments
 (0)