Skip to content

Commit

Permalink
rename parameters and update drivable area design md
Browse files Browse the repository at this point in the history
Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp>
  • Loading branch information
mkquda committed Mar 4, 2025
1 parent ef733b1 commit ff2c2a3
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,14 @@
extra_front_overhang: 0.5 # [m] extra length to add to the front overhang
extra_width: 1.0 # [m] extra length to add to the width
object_exclusion:
exclude_static: false # if true, the drivable area is not expanded over static objects
exclude_static: true # if true, the drivable area is not expanded over static objects
exclude_dynamic: false # if true, the drivable area is not expanded in the predicted path of dynamic objects
stopped_object_velocity_threshold: 1.0 # [m/s] velocity threshold for static objects
extra_footprint_offset:
front: 0.5 # [m] extra length to add to the front of object footprint
rear: 0.5 # [m] extra length to add to the rear of object footprint
left: 0.5 # [m] extra length to add to the left of object footprint
right: 0.5 # [m] extra length to add to the rear of object footprint
th_stopped_object_velocity: 1.0 # [m/s] velocity threshold for static objects
safety_margin:
front: 0.75 # [m] margin to add to the front of object footprint
rear: 0.75 # [m] margin to add to the rear of object footprint
left: 0.75 # [m] margin to add to the left of object footprint
right: 0.75 # [m] margin to add to the rear of object footprint
path_preprocessing:
max_arc_length: 100.0 # [m] maximum arc length along the path where the ego footprint is projected (0.0 means no limit)
resample_interval: 2.0 # [m] fixed interval between resampled path points (0.0 means path points are directly used)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -826,16 +826,16 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam(
parameters, DrivableAreaExpansionParameters::EGO_EXTRA_WIDTH,
planner_data_->drivable_area_expansion_parameters.extra_width);
update_param(
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_FRONT,
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_FRONT,
planner_data_->drivable_area_expansion_parameters.object_exclusion.front_offset);
update_param(
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_REAR,
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_REAR,
planner_data_->drivable_area_expansion_parameters.object_exclusion.rear_offset);
update_param(
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_LEFT,
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_LEFT,
planner_data_->drivable_area_expansion_parameters.object_exclusion.left_offset);
update_param(
parameters, DrivableAreaExpansionParameters::OBJECTS_EXTRA_OFFSET_RIGHT,
parameters, DrivableAreaExpansionParameters::OBJECTS_SAFE_MARGIN_RIGHT,
planner_data_->drivable_area_expansion_parameters.object_exclusion.right_offset);
update_param(
parameters, DrivableAreaExpansionParameters::STOPPED_OBJ_VEL_THRESH,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,13 @@ Currently, when clipping left bound or right bound, it can clip the bound more t
| ego.extra_wheel_base | [m] | double | extra ego wheelbase | 0.0 |
| ego.extra_front_overhang | [m] | double | extra ego overhang | 0.5 |
| ego.extra_width | [m] | double | extra ego width | 1.0 |
| dynamic_objects.avoid | [-] | boolean | if true, the drivable area is not expanded in the predicted path of dynamic objects | true |
| dynamic_objects.extra_footprint_offset.front | [m] | double | extra length to add to the front of the ego footprint | 0.5 |
| dynamic_objects.extra_footprint_offset.rear | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
| dynamic_objects.extra_footprint_offset.left | [m] | double | extra length to add to the left of the ego footprint | 0.5 |
| dynamic_objects.extra_footprint_offset.right | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
| object_exclusion.exclude_static | [-] | boolean | if true, the drivable area is not expanded over static objects | true |
| object_exclusion.exclude_dynamic | [-] | boolean | if true, the drivable area is not expanded in the predicted path of dynamic objects | true |
| object_exclusion.th_stopped_object_velocity | [m/s] | double | extra length to add to the front of the ego footprint | 0.5 |
| object_exclusion.safety_margin.front | [m] | double | extra length to add to the front of the ego footprint | 0.5 |
| object_exclusion.safety_margin.rear | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
| object_exclusion.safety_margin.left | [m] | double | extra length to add to the left of the ego footprint | 0.5 |
| object_exclusion.safety_margin.right | [m] | double | extra length to add to the rear of the ego footprint | 0.5 |
| 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 |
| path_preprocessing.resample_interval | [m] | double | fixed interval between resampled path points (0.0 means path points are directly used) | 2.0 |
| 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 |
Expand Down Expand Up @@ -133,9 +135,14 @@ This equation was derived from the work of [Lim, H., Kim, C., and Jo, A., "Model

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

##### 3 Calculate maximum expansion distances of each bound point based on dynamic objects and linestring of the vector map (optional)
##### 3 Calculate maximum expansion distances of each bound point based on detected objects and linestring of the vector map (optional)

For each drivable area bound point, we calculate its maximum expansion distance as its distance to the closest "obstacle" which could be:

1. Map linestring with type `avoid_linestrings.type`.
2. Static object footprint (if `object_exclusion.exclude_static` is set to `true`).
3. Dynamic object path footprint (if `object_exclusion.exclude_dynamic` is set to `true`).

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`).
If `max_expansion_distance` is not `0.0`, it is use here if smaller than the distance to the closest obstacle.

![max distances](../images/drivable_area/DynamicDrivableArea-MaxWidth.drawio.svg)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,16 +33,16 @@ struct DrivableAreaExpansionParameters
static constexpr auto EGO_EXTRA_FRONT_OVERHANG = "dynamic_expansion.ego.extra_front_overhang";
static constexpr auto EGO_EXTRA_WHEELBASE = "dynamic_expansion.ego.extra_wheelbase";
static constexpr auto EGO_EXTRA_WIDTH = "dynamic_expansion.ego.extra_width";
static constexpr auto OBJECTS_EXTRA_OFFSET_FRONT =
"dynamic_expansion.object_exclusion.extra_footprint_offset.front";
static constexpr auto OBJECTS_EXTRA_OFFSET_REAR =
"dynamic_expansion.object_exclusion.extra_footprint_offset.rear";
static constexpr auto OBJECTS_EXTRA_OFFSET_LEFT =
"dynamic_expansion.object_exclusion.extra_footprint_offset.left";
static constexpr auto OBJECTS_EXTRA_OFFSET_RIGHT =
"dynamic_expansion.object_exclusion.extra_footprint_offset.right";
static constexpr auto OBJECTS_SAFE_MARGIN_FRONT =
"dynamic_expansion.object_exclusion.safety_margin.front";
static constexpr auto OBJECTS_SAFE_MARGIN_REAR =
"dynamic_expansion.object_exclusion.safety_margin.rear";
static constexpr auto OBJECTS_SAFE_MARGIN_LEFT =
"dynamic_expansion.object_exclusion.safety_margin.left";
static constexpr auto OBJECTS_SAFE_MARGIN_RIGHT =
"dynamic_expansion.object_exclusion.safety_margin.right";
static constexpr auto STOPPED_OBJ_VEL_THRESH =
"dynamic_expansion.object_exclusion.stopped_object_velocity_threshold";
"dynamic_expansion.object_exclusion.th_stopped_object_velocity";
static constexpr auto MAX_EXP_DIST_PARAM = "dynamic_expansion.max_expansion_distance";
static constexpr auto RESAMPLE_INTERVAL_PARAM =
"dynamic_expansion.path_preprocessing.resample_interval";
Expand Down Expand Up @@ -121,10 +121,10 @@ struct DrivableAreaExpansionParameters
object_exclusion.exclude_static = node.declare_parameter<bool>(AVOID_STA_OBJECTS_PARAM);
object_exclusion.exclude_dynamic = node.declare_parameter<bool>(AVOID_DYN_OBJECTS_PARAM);
object_exclusion.stopped_obj_vel_th = node.declare_parameter<double>(STOPPED_OBJ_VEL_THRESH);
object_exclusion.front_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_FRONT);
object_exclusion.rear_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_REAR);
object_exclusion.left_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_LEFT);
object_exclusion.right_offset = node.declare_parameter<double>(OBJECTS_EXTRA_OFFSET_RIGHT);
object_exclusion.front_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_FRONT);
object_exclusion.rear_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_REAR);
object_exclusion.left_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_LEFT);
object_exclusion.right_offset = node.declare_parameter<double>(OBJECTS_SAFE_MARGIN_RIGHT);
avoid_linestring_types =
node.declare_parameter<std::vector<std::string>>(AVOID_LINESTRING_TYPES_PARAM);
avoid_linestring_dist = node.declare_parameter<double>(AVOID_LINESTRING_DIST_PARAM);
Expand Down

0 comments on commit ff2c2a3

Please sign in to comment.