Skip to content

Commit

Permalink
migrating
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin authored and kyoichi-sugahara committed Dec 20, 2024
1 parent 0b6198e commit 425eed8
Show file tree
Hide file tree
Showing 30 changed files with 3,253 additions and 1,695 deletions.
Original file line number Diff line number Diff line change
@@ -1,19 +1,24 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_behavior_path_goal_planner_module)

set(ament_cmake_lint_cmake_FOUND TRUE)

find_package(autoware_cmake REQUIRED)
autoware_package()
pluginlib_export_plugin_description_file(autoware_behavior_path_planner plugins.xml)

ament_auto_add_library(${PROJECT_NAME} SHARED
src/pull_over_planner/pull_over_planner_base.cpp
src/pull_over_planner/freespace_pull_over.cpp
src/pull_over_planner/geometric_pull_over.cpp
src/pull_over_planner/shift_pull_over.cpp
src/default_fixed_goal_planner.cpp
src/freespace_pull_over.cpp
src/geometric_pull_over.cpp
src/goal_searcher.cpp
src/shift_pull_over.cpp
src/util.cpp
src/goal_planner_module.cpp
src/manager.cpp
src/thread_data.cpp
src/decision_state.cpp
)

ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
Expand Up @@ -173,20 +173,19 @@ The gray numbers represent objects to avoid, and you can see that the goal in fr

### Parameters for goal search

| Name | Unit | Type | Description | Default value |
| :------------------------------ | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------- |
| goal_priority | [-] | string | In case `minimum_longitudinal_distance`, sort with smaller longitudinal distances taking precedence over smaller lateral distances. In case `minimum_weighted_distance`, sort with the sum of weighted lateral distance and longitudinal distance | `minimum_weighted_distance` |
| lateral_weight | [-] | double | Weight for lateral distance used when `minimum_weighted_distance` | 40.0 |
| prioritize_goals_before_objects | [-] | bool | If there are objects that may need to be avoided, prioritize the goal in front of them | true |
| forward_goal_search_length | [m] | double | length of forward range to be explored from the original goal | 20.0 |
| backward_goal_search_length | [m] | double | length of backward range to be explored from the original goal | 20.0 |
| goal_search_interval | [m] | double | distance interval for goal search | 2.0 |
| longitudinal_margin | [m] | double | margin between ego-vehicle at the goal position and obstacles | 3.0 |
| max_lateral_offset | [m] | double | maximum offset of goal search in the lateral direction | 0.5 |
| lateral_offset_interval | [m] | double | distance interval of goal search in the lateral direction | 0.25 |
| ignore_distance_from_lane_start | [m] | double | distance from start of pull over lanes for ignoring goal candidates | 0.0 |
| ignore_distance_from_lane_start | [m] | double | distance from start of pull over lanes for ignoring goal candidates | 0.0 |
| margin_from_boundary | [m] | double | distance margin from edge of the shoulder lane | 0.5 |
| Name | Unit | Type | Description | Default value |
| :------------------------------ | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :-------------------------- |
| goal_priority | [-] | string | In case `minimum_longitudinal_distance`, sort with smaller longitudinal distances taking precedence over smaller lateral distances. In case `minimum_weighted_distance`, sort with the sum of weighted lateral distance and longitudinal distance | `minimum_weighted_distance` |
| lateral_weight | [-] | double | Weight for lateral distance used when `minimum_weighted_distance` | 40.0 |
| prioritize_goals_before_objects | [-] | bool | If there are objects that may need to be avoided, prioritize the goal in front of them | true |
| forward_goal_search_length | [m] | double | length of forward range to be explored from the original goal | 20.0 |
| backward_goal_search_length | [m] | double | length of backward range to be explored from the original goal | 20.0 |
| goal_search_interval | [m] | double | distance interval for goal search | 2.0 |
| longitudinal_margin | [m] | double | margin between ego-vehicle at the goal position and obstacles | 3.0 |
| max_lateral_offset | [m] | double | maximum offset of goal search in the lateral direction | 0.5 |
| lateral_offset_interval | [m] | double | distance interval of goal search in the lateral direction | 0.25 |
| ignore_distance_from_lane_start | [m] | double | This parameter ensures that the distance between the start of the shoulder lane and the goal is not less than the specified value. It's used to prevent setting goals too close to the beginning of the shoulder lane, which might lead to unsafe or impractical pull-over maneuvers. Increasing this value will force the system to ignore potential goal positions near the start of the shoulder lane, potentially leading to safer and more comfortable pull-over locations. | 0.0 |
| margin_from_boundary | [m] | double | distance margin from edge of the shoulder lane | 0.5 |

## **Pull Over**

Expand Down Expand Up @@ -340,13 +339,13 @@ Then there is the concept of soft and hard margins. Although not currently param

#### Parameters for object recognition based collision check

| Name | Unit | Type | Description | Default value |
| :----------------------------------------------------------- | :--- | :------------- | :------------------------------------------------------------------------------------------------------- | :-------------- |
| use_object_recognition | [-] | bool | flag whether to use object recognition for collision check | true |
| object_recognition_collision_check_soft_margins | [m] | vector[double] | soft margins for collision check when path generation | [2.0, 1.5, 1.0] |
| object_recognition_collision_check_hard_margins | [m] | vector[double] | hard margins for collision check when path generation | [0.6] |
| object_recognition_collision_check_max_extra_stopping_margin | [m] | double | maximum value when adding longitudinal distance margin for collision check considering stopping distance | 1.0 |
| detection_bound_offset | [m] | double | expand pull over lane with this offset to make detection area for collision check of path generation | 15.0 |
| Name | Unit | Type | Description | Default value |
| :----------------------------------------------------------- | :--- | :------------- | :--------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :-------------------------------------------- |
| use_object_recognition | [-] | bool | flag whether to use object recognition for collision check | true |
| object_recognition_collision_check_soft_margins | [m] | vector[double] | soft margins for collision check when path generation. It is not strictly the distance between footprints, but the maximum distance when ego and objects are oriented. | [5.0, 4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0] |
| object_recognition_collision_check_hard_margins | [m] | vector[double] | hard margins for collision check when path generation | [0.6] |
| object_recognition_collision_check_max_extra_stopping_margin | [m] | double | maximum value when adding longitudinal distance margin for collision check considering stopping distance | 1.0 |
| detection_bound_offset | [m] | double | expand pull over lane with this offset to make detection area for collision check of path generation | 15.0 |

## **safety check**

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@
ignore_distance_from_lane_start: 0.0
margin_from_boundary: 0.5
high_curvature_threshold: 0.1
bus_stop_area:
use_bus_stop_area: false
goal_search_interval: 0.5
lateral_offset_interval: 0.25

# occupancy grid map
occupancy_grid:
Expand Down
Loading

0 comments on commit 425eed8

Please sign in to comment.