Skip to content

Commit

Permalink
fix(behavior_path_planner): fix pull_over request_length and maximum_…
Browse files Browse the repository at this point in the history
…deceleration (#1789)

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 authored Sep 6, 2022
1 parent 5b30e50 commit 165f29e
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 14 deletions.
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
/**:
ros__parameters:
pull_over:
request_length: 100.0
request_length: 200.0
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 2.0 # It must be greater than the state_machine's.
pull_over_velocity: 3.0
pull_over_minimum_velocity: 0.3
margin_from_boundary: 0.5
decide_path_distance: 10.0
maximum_deceleration: 0.5
maximum_deceleration: 1.0
# goal research
enable_goal_research: true
search_priority: "efficient_path" # "efficient_path" or "close_goal"
Expand Down
18 changes: 9 additions & 9 deletions planning/behavior_path_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ The Pull Over module is activated when goal is in the shoulder lane. Ego-vehicle

- The goal is in shoulder lane and the ego-vehicle is in road lane.
- The distance between the goal and ego-vehicle is somewhat close.
- It is shorter than `request_length`(default: < `100m`).
- It is shorter than `request_length`(default: < `200m`).

- Pull over ready condition

Expand All @@ -220,15 +220,15 @@ The Pull Over module is activated when goal is in the shoulder lane. Ego-vehicle

| Name | Unit | Type | Description | Default value |
| :------------------------- | :----- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
| request_length | [m] | double | when the ego-vehicle approaches the goal by this distance, the module is activated. | 100.0 |
| request_length | [m] | double | when the ego-vehicle approaches the goal by this distance, the module is activated. | 200.0 |
| th_arrived_distance | [m] | double | distance threshold for arrival of path termination | 1.0 |
| th_stopped_velocity | [m/s] | double | velocity threshold for arrival of path termination | 0.01 |
| th_stopped_time | [s] | double | time threshold for arrival of path termination | 2.0 |
| pull_over_velocity | [m/s] | double | decelerate to this speed by the goal search area | 2.0 |
| pull_over_minimum_velocity | [m/s] | double | speed of pull_over after stopping once. this prevents excessive acceleration. | 0.3 |
| margin_from_boundary | [m] | double | distance margin from edge of the shoulder lane | 0.5 |
| decide_path_distance | [m] | double | decide path if it approaches this distance relative to the parking position. after that, no path planning and goal search are performed | 10.0 |
| maximum_deceleration | [m/s2] | double | maximum deceleration. it prevents sudden deceleration when a parking path cannot be found suddenly | 0.5 |
| maximum_deceleration | [m/s2] | double | maximum deceleration. it prevents sudden deceleration when a parking path cannot be found suddenly | 1.0 |

#### **collision check**

Expand Down Expand Up @@ -322,12 +322,12 @@ Generate two forward arc paths.

###### Parameters arc forward parking

| Name | Unit | Type | Description | Default value |
| :-------------------------------------- | :---- | :----- | :------------------------------------------------------------------------------- | :------------ |
| enable_arc_forward_parking | [-] | bool | flag whether to enable arc forward parking | true |
| after_forward_parking_straight_distance | [m] | double | straight line distance after pull over end point | 2.0 |
| forward_parking_velocity | [m/s] | double | velocity when forward parking | 0.3 |
| forward_parking_lane_departure_margin | [m/s] | double | lane departure margin for front left corner of ego-vehicle when forkward parking | 0.0 |
| Name | Unit | Type | Description | Default value |
| :-------------------------------------- | :---- | :----- | :------------------------------------------------------------------------------ | :------------ |
| enable_arc_forward_parking | [-] | bool | flag whether to enable arc forward parking | true |
| after_forward_parking_straight_distance | [m] | double | straight line distance after pull over end point | 2.0 |
| forward_parking_velocity | [m/s] | double | velocity when forward parking | 0.3 |
| forward_parking_lane_departure_margin | [m/s] | double | lane departure margin for front left corner of ego-vehicle when forward parking | 0.0 |

###### arc backward parking

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
pull_over_minimum_velocity: 0.3
margin_from_boundary: 0.5
decide_path_distance: 10.0
maximum_deceleration: 0.5
maximum_deceleration: 1.0
# goal research
enable_goal_research: true
search_priority: "efficient_path" # "efficient_path" or "close_goal"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -364,13 +364,13 @@ PullOverParameters BehaviorPathPlannerNode::getPullOverParam()
};

PullOverParameters p;
p.request_length = dp("request_length", 100.0);
p.request_length = dp("request_length", 200.0);
p.th_stopped_velocity = dp("th_stopped_velocity", 0.01);
p.th_arrived_distance = dp("th_arrived_distance", 0.3);
p.th_stopped_time = dp("th_stopped_time", 2.0);
p.margin_from_boundary = dp("margin_from_boundary", 0.3);
p.decide_path_distance = dp("decide_path_distance", 10.0);
p.maximum_deceleration = dp("maximum_deceleration", 0.5);
p.maximum_deceleration = dp("maximum_deceleration", 1.0);
// goal research
p.enable_goal_research = dp("enable_goal_research", true);
p.search_priority = dp("search_priority", "efficient_path");
Expand Down

0 comments on commit 165f29e

Please sign in to comment.