Skip to content

Commit

Permalink
feat(behavior_path_planner): update behavior param file (#3220)
Browse files Browse the repository at this point in the history
* feat(behavior_path_planner): add new config file for manger

Signed-off-by: satoshi-ota <[email protected]>

* feat(launch): add config path

Signed-off-by: satoshi-ota <[email protected]>

* fix(behavior_path_planner): add missing param file

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Mar 31, 2023
1 parent 33092b0 commit e8c1d73
Show file tree
Hide file tree
Showing 3 changed files with 113 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ def launch_setup(context, *args, **kwargs):
pull_out_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("drivable_area_expansion_param_path").perform(context), "r") as f:
drivable_area_expansion_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("scene_module_manager_param_path").perform(context), "r") as f:
scene_module_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(LaunchConfiguration("behavior_path_planner_param_path").perform(context), "r") as f:
behavior_path_planner_param = yaml.safe_load(f)["/**"]["ros__parameters"]

Expand Down Expand Up @@ -88,6 +90,7 @@ def launch_setup(context, *args, **kwargs):
pull_over_param,
pull_out_param,
drivable_area_expansion_param,
scene_module_manager_param,
behavior_path_planner_param,
vehicle_param,
{
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
/**:
ros__parameters:
# Static expansion
avoidance:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]
lane_change:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]
lane_following:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]
pull_out:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]
pull_over:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]
side_shift:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
drivable_area_types_to_skip: [road_border]

# Dynamic expansion by projecting the ego footprint along the path
dynamic_expansion:
enabled: false
ego:
extra_footprint_offset:
front: 0.5 # [m] extra length to add to the front of the ego footprint
rear: 0.5 # [m] extra length to add to the rear of the ego footprint
left: 0.5 # [m] extra length to add to the left of the ego footprint
right: 0.5 # [m] extra length to add to the rear of the ego footprint
dynamic_objects:
avoid: true # if true, the drivable area is not expanded in the predicted path of dynamic objects
extra_footprint_offset:
front: 0.5 # [m] extra length to add to the front of the dynamic object footprint
rear: 0.5 # [m] extra length to add to the rear of the dynamic object footprint
left: 0.5 # [m] extra length to add to the left of the dynamic object footprint
right: 0.5 # [m] extra length to add to the rear of the dynamic object footprint
expansion:
method: polygon # method used to expand the drivable area. Either 'lanelet' or 'polygon'.
# 'lanelet': add lanelets overlapped by the ego footprints
# 'polygon': add polygons built around sections of the ego footprint that go out of the drivable area
max_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit)
max_path_arc_length: 50.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit)
extra_arc_length: 0.5 # [m] extra expansion arc length around an ego footprint
avoid_linestring:
types: # linestring types in the lanelet maps that will not be crossed when expanding the drivable area
- road_border
distance: 0.0 # [m] distance to keep between the drivable area and the linestrings to avoid
compensate:
enable: true # if true, when the drivable area cannot be expanded in one direction to completely include the ego footprint, it is expanded in the opposite direction
extra_distance: 3.0 # [m] extra distance to add to the compensation
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
# USE ONLY WHEN THE OPTION COMPILE_WITH_OLD_ARCHITECTURE IS SET TO FALSE.
# https://github.com/autowarefoundation/autoware.universe/blob/main/planning/behavior_path_planner/CMakeLists.txt
# NOTE: The smaller the priority number is, the higher the module priority is.
/**:
ros__parameters:
ext_request_lane_change_left:
enable_module: false
enable_simultaneous_execution: false
priority: 6
max_module_size: 1

ext_request_lane_change_right:
enable_module: false
enable_simultaneous_execution: false
priority: 6
max_module_size: 1

lane_change_left:
enable_module: true
enable_simultaneous_execution: true
priority: 5
max_module_size: 1

lane_change_right:
enable_module: true
enable_simultaneous_execution: false
priority: 4
max_module_size: 1

pull_out:
enable_module: true
enable_simultaneous_execution: false
priority: 0
max_module_size: 1

side_shift:
enable_module: true
enable_simultaneous_execution: false
priority: 2
max_module_size: 1

pull_over:
enable_module: true
enable_simultaneous_execution: false
priority: 1
max_module_size: 1

avoidance:
enable_module: true
enable_simultaneous_execution: false
priority: 3
max_module_size: 1

0 comments on commit e8c1d73

Please sign in to comment.