Skip to content

Commit aafade9

Browse files
committed
correct parameters description
Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp>
1 parent c7eb2f0 commit aafade9

File tree

3 files changed

+37
-32
lines changed

3 files changed

+37
-32
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md

+23-23
Original file line numberDiff line numberDiff line change
@@ -32,29 +32,29 @@ Currently, when clipping left bound or right bound, it can clip the bound more t
3232

3333
### Dynamic expansion
3434

35-
| Name | Unit | Type | Description | Default value |
36-
| :------------------------------------------- | :---- | :----------- | :------------------------------------------------------------------------------------------------------ | :--------------------------- |
37-
| enabled | [-] | boolean | if true, dynamically expand the drivable area based on the path curvature | true |
38-
| print_runtime | [-] | boolean | if true, runtime is logged by the node | true |
39-
| max_expansion_distance | [m] | double | maximum distance by which the original drivable area can be expanded (no limit if set to 0) | 0.0 |
40-
| smoothing.curvature_average_window | [-] | int | window size used for smoothing the curvatures using a moving window average | 3 |
41-
| smoothing.max_bound_rate | [m/m] | double | maximum rate of change of the bound lateral distance over its arc length | 1.0 |
42-
| smoothing.arc_length_range | [m] | double | arc length range where an expansion distance is initially applied | 2.0 |
43-
| ego.extra_wheel_base | [m] | double | extra ego wheelbase | 0.0 |
44-
| ego.extra_front_overhang | [m] | double | extra ego overhang | 0.5 |
45-
| ego.extra_width | [m] | double | extra ego width | 1.0 |
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 right of the ego footprint | 0.5 |
53-
| 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 |
54-
| path_preprocessing.resample_interval | [m] | double | fixed interval between resampled path points (0.0 means path points are directly used) | 2.0 |
55-
| 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 |
56-
| avoid_linestring.types | [-] | string array | linestring types in the lanelet maps that will not be crossed when expanding the drivable area | ["road_border", "curbstone"] |
57-
| avoid_linestring.distance | [m] | double | distance to keep between the drivable area and the linestrings to avoid | 0.0 |
35+
| Name | Unit | Type | Description | Default value |
36+
| :------------------------------------------ | :---- | :----------- | :------------------------------------------------------------------------------------------------------ | :--------------------------- |
37+
| enabled | [-] | boolean | if true, dynamically expand the drivable area based on the path curvature | true |
38+
| print_runtime | [-] | boolean | if true, runtime is logged by the node | true |
39+
| max_expansion_distance | [m] | double | maximum distance by which the original drivable area can be expanded (no limit if set to 0) | 0.0 |
40+
| smoothing.curvature_average_window | [-] | int | window size used for smoothing the curvatures using a moving window average | 3 |
41+
| smoothing.max_bound_rate | [m/m] | double | maximum rate of change of the bound lateral distance over its arc length | 1.0 |
42+
| smoothing.arc_length_range | [m] | double | arc length range where an expansion distance is initially applied | 2.0 |
43+
| ego.extra_wheel_base | [m] | double | extra ego wheelbase | 0.0 |
44+
| ego.extra_front_overhang | [m] | double | extra ego overhang | 0.5 |
45+
| ego.extra_width | [m] | double | extra ego width | 1.0 |
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 | velocity threshold for static objects | 1.0 |
49+
| object_exclusion.safety_margin.front | [m] | double | extra length to add to the front of the object footprint | 0.75 |
50+
| object_exclusion.safety_margin.rear | [m] | double | extra length to add to the rear of the object footprint | 0.75 |
51+
| object_exclusion.safety_margin.left | [m] | double | extra length to add to the left of the object footprint | 0.75 |
52+
| object_exclusion.safety_margin.right | [m] | double | extra length to add to the right of the object footprint | 0.75 |
53+
| 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 |
54+
| path_preprocessing.resample_interval | [m] | double | fixed interval between resampled path points (0.0 means path points are directly used) | 2.0 |
55+
| 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 |
56+
| avoid_linestring.types | [-] | string array | linestring types in the lanelet maps that will not be crossed when expanding the drivable area | ["road_border", "curbstone"] |
57+
| avoid_linestring.distance | [m] | double | distance to keep between the drivable area and the linestrings to avoid | 0.0 |
5858

5959
## Inner-workings / Algorithms
6060

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

+6-3
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,10 @@ struct DrivableAreaExpansionParameters
5050
"dynamic_expansion.path_preprocessing.max_arc_length";
5151
static constexpr auto MAX_REUSE_DEVIATION_PARAM =
5252
"dynamic_expansion.path_preprocessing.reuse_max_deviation";
53-
static constexpr auto AVOID_STA_OBJECTS_PARAM = "dynamic_expansion.object_exclusion.exclude_static";
54-
static constexpr auto AVOID_DYN_OBJECTS_PARAM = "dynamic_expansion.object_exclusion.exclude_dynamic";
53+
static constexpr auto AVOID_STA_OBJECTS_PARAM =
54+
"dynamic_expansion.object_exclusion.exclude_static";
55+
static constexpr auto AVOID_DYN_OBJECTS_PARAM =
56+
"dynamic_expansion.object_exclusion.exclude_dynamic";
5557
static constexpr auto AVOID_LINESTRING_TYPES_PARAM = "dynamic_expansion.avoid_linestring.types";
5658
static constexpr auto AVOID_LINESTRING_DIST_PARAM = "dynamic_expansion.avoid_linestring.distance";
5759
static constexpr auto SMOOTHING_CURVATURE_WINDOW_PARAM =
@@ -83,7 +85,8 @@ struct DrivableAreaExpansionParameters
8385
double min_bound_interval{};
8486
bool print_runtime{};
8587

86-
struct ObjectExclusion{
88+
struct ObjectExclusion
89+
{
8790
bool exclude_static{};
8891
bool exclude_dynamic{};
8992
double front_offset{};

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@
1515
#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/footprints.hpp"
1616

1717
#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp"
18-
1918
#include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
2019

2120
#include <autoware_utils/geometry/boost_polygon_utils.hpp>
@@ -74,11 +73,14 @@ MultiPolygon2d create_object_footprints(
7473
continue;
7574
}
7675

77-
if (params.object_exclusion.exclude_static && velocity_filter(
78-
object.kinematics.initial_twist_with_covariance.twist, -std::numeric_limits<double>::epsilon(),
79-
params.object_exclusion.stopped_obj_vel_th)) {
80-
footprints.push_back(create_footprint(object.kinematics.initial_pose_with_covariance.pose, base_footprint));
81-
}
76+
if (
77+
params.object_exclusion.exclude_static &&
78+
velocity_filter(
79+
object.kinematics.initial_twist_with_covariance.twist,
80+
-std::numeric_limits<double>::epsilon(), params.object_exclusion.stopped_obj_vel_th)) {
81+
footprints.push_back(
82+
create_footprint(object.kinematics.initial_pose_with_covariance.pose, base_footprint));
83+
}
8284
}
8385
return footprints;
8486
}

0 commit comments

Comments
 (0)