Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit a9d8fb8

Browse files
committedMar 21, 2025·
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 3b269a9 commit a9d8fb8

File tree

6 files changed

+19
-16
lines changed

6 files changed

+19
-16
lines changed
 

‎planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ struct ParallelParkingParameters
6161
double pull_out_velocity{0.0};
6262
double pull_out_lane_departure_margin{0.0};
6363
double pull_out_arc_path_interval{0.0};
64-
double pull_out_max_steer_angle{0.0};
64+
double geometric_pull_out_max_steer_angle_margin_scale{0.0};
6565
};
6666

6767
class GeometricParallelParking

‎planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md

+8-8
Original file line numberDiff line numberDiff line change
@@ -494,14 +494,14 @@ See also [[1]](https://www.sciencedirect.com/science/article/pii/S14746670153474
494494

495495
#### parameters for geometric pull out
496496

497-
| Name | Unit | Type | Description | Default value |
498-
| :------------------------------------ | :---- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
499-
| enable_geometric_pull_out | [-] | bool | flag whether to enable geometric pull out | true |
500-
| divide_pull_out_path | [-] | bool | flag whether to divide arc paths. The path is assumed to be divided because the curvature is not continuous. But it requires a stop during the departure. | false |
501-
| geometric_pull_out_velocity | [m/s] | double | velocity of geometric pull out | 1.0 |
502-
| lane_departure_margin | [m] | double | margin of deviation to lane right | 0.2 |
503-
| lane_departure_check_expansion_margin | [m] | double | margin to expand the ego vehicle footprint when doing lane departure checks | 0.0 |
504-
| pull_out_max_steer_angle | [rad] | double | maximum steer angle for path generation | 0.26 |
497+
| Name | Unit | Type | Description | Default value |
498+
| :---------------------------------------------- | :---- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
499+
| enable_geometric_pull_out | [-] | bool | flag whether to enable geometric pull out | true |
500+
| divide_pull_out_path | [-] | bool | flag whether to divide arc paths. The path is assumed to be divided because the curvature is not continuous. But it requires a stop during the departure. | false |
501+
| geometric_pull_out_velocity | [m/s] | double | velocity of geometric pull out | 1.0 |
502+
| lane_departure_margin | [m] | double | margin of deviation to lane right | 0.2 |
503+
| lane_departure_check_expansion_margin | [m] | double | margin to expand the ego vehicle footprint when doing lane departure checks | 0.0 |
504+
| geometric_pull_out_max_steer_angle_margin_scale | [-] | double | scaling factor applied to the maximum steering angle (max_steer_angle) defined in vehicle_info parameter | 0.72 |
505505

506506
## **backward pull out start point search**
507507

‎planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@
4343
lane_departure_margin: 0.2
4444
lane_departure_check_expansion_margin: 0.0
4545
backward_velocity: -1.0
46-
pull_out_max_steer_angle: 0.26 # 15deg
46+
geometric_pull_out_max_steer_angle_margin_scale: 0.72
4747
# search start pose backward
4848
enable_back: true
4949
search_priority: "efficient_path" # "efficient_path" or "short_back_distance"

‎planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/data_structs.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -84,8 +84,9 @@ StartPlannerParameters StartPlannerParameters::init(rclcpp::Node & node)
8484
get_or_declare_parameter<double>(node, ns + "lane_departure_margin");
8585
p.lane_departure_check_expansion_margin =
8686
get_or_declare_parameter<double>(node, ns + "lane_departure_check_expansion_margin");
87-
p.parallel_parking_parameters.pull_out_max_steer_angle =
88-
get_or_declare_parameter<double>(node, ns + "pull_out_max_steer_angle"); // 15deg
87+
p.parallel_parking_parameters.geometric_pull_out_max_steer_angle_margin_scale =
88+
get_or_declare_parameter<double>(
89+
node, ns + "geometric_pull_out_max_steer_angle_margin_scale");
8990
p.parallel_parking_parameters.center_line_path_interval =
9091
p.center_line_path_interval; // for geometric parallel parking
9192
// search start pose backward

‎planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -65,9 +65,11 @@ std::optional<PullOutPath> GeometricPullOut::plan(
6565

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;
68+
const double max_steer_angle =
69+
vehicle_info_.max_steer_angle *
70+
parallel_parking_parameters_.geometric_pull_out_max_steer_angle_margin_scale;
6871

69-
planner_.setTurningRadius(
70-
planner_data->parameters, parallel_parking_parameters_.pull_out_max_steer_angle);
72+
planner_.setTurningRadius(planner_data->parameters, max_steer_angle);
7173
planner_.setPlannerData(planner_data);
7274
const bool found_valid_path = planner_.planPullOut(
7375
start_pose, goal_pose, road_lanes, pull_out_lanes, left_side_start, lane_departure_checker_);

‎planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -127,8 +127,8 @@ void StartPlannerModuleManager::updateModuleParams(
127127
parameters, ns + "lane_departure_check_expansion_margin",
128128
p->lane_departure_check_expansion_margin);
129129
update_param<double>(
130-
parameters, ns + "pull_out_max_steer_angle",
131-
p->parallel_parking_parameters.pull_out_max_steer_angle);
130+
parameters, ns + "geometric_pull_out_max_steer_angle_margin_scale",
131+
p->parallel_parking_parameters.geometric_pull_out_max_steer_angle_margin_scale);
132132
update_param<bool>(parameters, ns + "enable_back", p->enable_back);
133133
update_param<double>(parameters, ns + "backward_velocity", p->backward_velocity);
134134
update_param<double>(

0 commit comments

Comments
 (0)
Please sign in to comment.