Skip to content

Commit ff2c2a3

Browse files
committed
rename parameters and update drivable area design md
Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp>
1 parent ef733b1 commit ff2c2a3

File tree

4 files changed

+38
-31
lines changed

4 files changed

+38
-31
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner/config/drivable_area_expansion.param.yaml

+7-7
Original file line numberDiff line numberDiff line change
@@ -20,14 +20,14 @@
2020
extra_front_overhang: 0.5 # [m] extra length to add to the front overhang
2121
extra_width: 1.0 # [m] extra length to add to the width
2222
object_exclusion:
23-
exclude_static: false # if true, the drivable area is not expanded over static objects
23+
exclude_static: true # if true, the drivable area is not expanded over static objects
2424
exclude_dynamic: false # if true, the drivable area is not expanded in the predicted path of dynamic objects
25-
stopped_object_velocity_threshold: 1.0 # [m/s] velocity threshold for static objects
26-
extra_footprint_offset:
27-
front: 0.5 # [m] extra length to add to the front of object footprint
28-
rear: 0.5 # [m] extra length to add to the rear of object footprint
29-
left: 0.5 # [m] extra length to add to the left of object footprint
30-
right: 0.5 # [m] extra length to add to the rear of object footprint
25+
th_stopped_object_velocity: 1.0 # [m/s] velocity threshold for static objects
26+
safety_margin:
27+
front: 0.75 # [m] margin to add to the front of object footprint
28+
rear: 0.75 # [m] margin to add to the rear of object footprint
29+
left: 0.75 # [m] margin to add to the left of object footprint
30+
right: 0.75 # [m] margin to add to the rear of object footprint
3131
path_preprocessing:
3232
max_arc_length: 100.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit)
3333
resample_interval: 2.0 # [m] fixed interval between resampled path points (0.0 means path points are directly used)

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -826,16 +826,16 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam(
826826
parameters, DrivableAreaExpansionParameters::EGO_EXTRA_WIDTH,
827827
planner_data_->drivable_area_expansion_parameters.extra_width);
828828
update_param(
829-
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_FRONT,
829+
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_FRONT,
830830
planner_data_->drivable_area_expansion_parameters.object_exclusion.front_offset);
831831
update_param(
832-
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_REAR,
832+
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_REAR,
833833
planner_data_->drivable_area_expansion_parameters.object_exclusion.rear_offset);
834834
update_param(
835-
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_LEFT,
835+
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_LEFT,
836836
planner_data_->drivable_area_expansion_parameters.object_exclusion.left_offset);
837837
update_param(
838-
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_RIGHT,
838+
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_RIGHT,
839839
planner_data_->drivable_area_expansion_parameters.object_exclusion.right_offset);
840840
update_param(
841841
parameters, DrivableAreaExpansionParameters::STOPPED_OBJ_VEL_THRESH,

planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md

+14-7
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,13 @@ Currently, when clipping left bound or right bound, it can clip the bound more t
4343
| ego.extra_wheel_base | [m] | double | extra ego wheelbase | 0.0 |
4444
| ego.extra_front_overhang | [m] | double | extra ego overhang | 0.5 |
4545
| ego.extra_width | [m] | double | extra ego width | 1.0 |
46-
| dynamic_objects.avoid | [-] | boolean | if true, the drivable area is not expanded in the predicted path of dynamic objects | true |
47-
| dynamic_objects.extra_footprint_offset.front | [m] | double | extra length to add to the front of the ego footprint | 0.5 |
48-
| dynamic_objects.extra_footprint_offset.rear | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
49-
| dynamic_objects.extra_footprint_offset.left | [m] | double | extra length to add to the left of the ego footprint | 0.5 |
50-
| dynamic_objects.extra_footprint_offset.right | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
46+
| object_exclusion.exclude_static | [-] | boolean | if true, the drivable area is not expanded over static objects | true |
47+
| object_exclusion.exclude_dynamic | [-] | boolean | if true, the drivable area is not expanded in the predicted path of dynamic objects | true |
48+
| object_exclusion.th_stopped_object_velocity | [m/s] | double | extra length to add to the front of the ego footprint | 0.5 |
49+
| object_exclusion.safety_margin.front | [m] | double | extra length to add to the front of the ego footprint | 0.5 |
50+
| object_exclusion.safety_margin.rear | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
51+
| object_exclusion.safety_margin.left | [m] | double | extra length to add to the left of the ego footprint | 0.5 |
52+
| object_exclusion.safety_margin.right | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
5153
| path_preprocessing.max_arc_length | [m] | double | maximum arc length along the path where the ego footprint is projected (0.0 means no limit) | 100.0 |
5254
| path_preprocessing.resample_interval | [m] | double | fixed interval between resampled path points (0.0 means path points are directly used) | 2.0 |
5355
| path_preprocessing.reuse_max_deviation | [m] | double | if the path changes by more than this value, the curvatures are recalculated. Otherwise they are reused | 0.5 |
@@ -133,9 +135,14 @@ This equation was derived from the work of [Lim, H., Kim, C., and Jo, A., "Model
133135

134136
![min width](../images/drivable_area/DynamicDrivableArea-MinWidth.drawio.svg)
135137

136-
##### 3 Calculate maximum expansion distances of each bound point based on dynamic objects and linestring of the vector map (optional)
138+
##### 3 Calculate maximum expansion distances of each bound point based on detected objects and linestring of the vector map (optional)
139+
140+
For each drivable area bound point, we calculate its maximum expansion distance as its distance to the closest "obstacle" which could be:
141+
142+
1. Map linestring with type `avoid_linestrings.type`.
143+
2. Static object footprint (if `object_exclusion.exclude_static` is set to `true`).
144+
3. Dynamic object path footprint (if `object_exclusion.exclude_dynamic` is set to `true`).
137145

138-
For each drivable area bound point, we calculate its maximum expansion distance as its distance to the closest "obstacle" (either a map linestring with type `avoid_linestrings.type`, or a dynamic object footprint if `dynamic_objects.avoid` is set to `true`).
139146
If `max_expansion_distance` is not `0.0`, it is use here if smaller than the distance to the closest obstacle.
140147

141148
![max distances](../images/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg)

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -33,16 +33,16 @@ struct DrivableAreaExpansionParameters
3333
static constexpr auto EGO_EXTRA_FRONT_OVERHANG = "dynamic_expansion.ego.extra_front_overhang";
3434
static constexpr auto EGO_EXTRA_WHEELBASE = "dynamic_expansion.ego.extra_wheelbase";
3535
static constexpr auto EGO_EXTRA_WIDTH = "dynamic_expansion.ego.extra_width";
36-
static constexpr auto OBJECTS_EXTRA_OFFSET_FRONT =
37-
"dynamic_expansion.object_exclusion.extra_footprint_offset.front";
38-
static constexpr auto OBJECTS_EXTRA_OFFSET_REAR =
39-
"dynamic_expansion.object_exclusion.extra_footprint_offset.rear";
40-
static constexpr auto OBJECTS_EXTRA_OFFSET_LEFT =
41-
"dynamic_expansion.object_exclusion.extra_footprint_offset.left";
42-
static constexpr auto OBJECTS_EXTRA_OFFSET_RIGHT =
43-
"dynamic_expansion.object_exclusion.extra_footprint_offset.right";
36+
static constexpr auto OBJECTS_SAFE_MARGIN_FRONT =
37+
"dynamic_expansion.object_exclusion.safety_margin.front";
38+
static constexpr auto OBJECTS_SAFE_MARGIN_REAR =
39+
"dynamic_expansion.object_exclusion.safety_margin.rear";
40+
static constexpr auto OBJECTS_SAFE_MARGIN_LEFT =
41+
"dynamic_expansion.object_exclusion.safety_margin.left";
42+
static constexpr auto OBJECTS_SAFE_MARGIN_RIGHT =
43+
"dynamic_expansion.object_exclusion.safety_margin.right";
4444
static constexpr auto STOPPED_OBJ_VEL_THRESH =
45-
"dynamic_expansion.object_exclusion.stopped_object_velocity_threshold";
45+
"dynamic_expansion.object_exclusion.th_stopped_object_velocity";
4646
static constexpr auto MAX_EXP_DIST_PARAM = "dynamic_expansion.max_expansion_distance";
4747
static constexpr auto RESAMPLE_INTERVAL_PARAM =
4848
"dynamic_expansion.path_preprocessing.resample_interval";
@@ -121,10 +121,10 @@ struct DrivableAreaExpansionParameters
121121
object_exclusion.exclude_static = node.declare_parameter<bool>(AVOID_STA_OBJECTS_PARAM);
122122
object_exclusion.exclude_dynamic = node.declare_parameter<bool>(AVOID_DYN_OBJECTS_PARAM);
123123
object_exclusion.stopped_obj_vel_th = node.declare_parameter<double>(STOPPED_OBJ_VEL_THRESH);
124-
object_exclusion.front_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_FRONT);
125-
object_exclusion.rear_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_REAR);
126-
object_exclusion.left_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_LEFT);
127-
object_exclusion.right_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_RIGHT);
124+
object_exclusion.front_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_FRONT);
125+
object_exclusion.rear_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_REAR);
126+
object_exclusion.left_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_LEFT);
127+
object_exclusion.right_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_RIGHT);
128128
avoid_linestring_types =
129129
node.declare_parameter<std::vector<std::string>>(AVOID_LINESTRING_TYPES_PARAM);
130130
avoid_linestring_dist = node.declare_parameter<double>(AVOID_LINESTRING_DIST_PARAM);

0 commit comments

Comments
 (0)