Skip to content

Commit 9f125cb

Browse files
feat(behavior_path_planner): better avoidance drivable areas extension in behavior path planning (autowarefoundation#287)
* feat: Increases the flexibility of the function in dealing with several scenarios The implementation updates generateExtendedDrivableArea this is a part of .iv PR (tier4/autoware.iv#2383) port Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * feat: change shift_length computation method The new method considers the availability of the lane on the left side or right side of ego vehicle, depending on the position of the obstacles. Will not generate avoidance path if the adjacent lane is not a lanelet. this is a part of .iv PR (tier4/autoware.iv#2383) port Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * feat: Adds documentation and debug marker visualization. The visualization will show the remaining distance between the overhang_pose and referenced linestring. this is a part of .iv PR (tier4/autoware.iv#2383) port Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix: change debug naming to show clearer intent The fix also removes a space character from one of the debug printing function call. Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix: replace equation from latex to math jax Also remove the equation's image Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix: equation spacing Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Fix: slight improvement in debug marker 1. Increase line ID text size and 2. Remove unnecessary visualization of connection between last point and the front point linestring. Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix: drivable area not extend to third lane during extension Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix: slightly increase lateral_collision_safety_buffer to 0.7 The decision to increase is based on discussion with the planning control team and also from input by FI team. Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
1 parent 0613d1d commit 9f125cb

22 files changed

+641
-36
lines changed

launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml

+7-1
Original file line numberDiff line numberDiff line change
@@ -7,11 +7,15 @@
77
detection_area_right_expand_dist: 0.0
88
detection_area_left_expand_dist: 1.0
99

10+
enable_avoidance_over_same_direction: true
11+
enable_avoidance_over_opposite_direction: true
12+
1013
threshold_distance_object_is_on_center: 1.0 # [m]
1114
threshold_speed_object_is_stopped: 1.0 # [m/s]
1215
object_check_forward_distance: 150.0 # [m]
1316
object_check_backward_distance: 2.0 # [m]
14-
lateral_collision_margin: 2.0 # [m]
17+
lateral_collision_margin: 1.0 # [m]
18+
lateral_collision_safety_buffer: 0.7 # [m]
1519

1620
prepare_time: 2.0 # [s]
1721
min_prepare_distance: 1.0 # [m]
@@ -20,6 +24,8 @@
2024
min_nominal_avoidance_speed: 7.0 # [m/s]
2125
min_sharp_avoidance_speed: 1.0 # [m/s]
2226

27+
road_shoulder_safety_margin: 0.5 # [m]
28+
2329
max_right_shift_length: 5.0
2430
max_left_shift_length: 5.0
2531

planning/behavior_path_planner/behavior_path_planner_avoidance-design.md

+145-1
Original file line numberDiff line numberDiff line change
@@ -238,6 +238,148 @@ The shift points are modified by a filtering process in order to get the expecte
238238
- Similar gradient removal: Connect two shift points with a straight line, and remove the shift points in between if their shift amount is in the vicinity of the straight line.
239239
- Remove momentary returns: For shift points that reduce the avoidance width (for going back to the center line), if there is enough long distance in the longitudinal direction, remove them.
240240

241+
#### Computing shift length (available as of develop/v0.25.0)
242+
243+
**Note**: This feature is available as of develop/`v0.25.0`.
244+
245+
The shift length is set as a constant value before the feature is implemented (develop/`v0.24.0` and below). Setting the shift length like this will cause the module to generate an avoidance path regardless of actual environmental properties. For example, the path might exceed the actual road boundary or go towards a wall. Therefore, to address this limitation, in addition to [how to decide the target obstacle](#how-to-decide-the-target-obstacles), the upgraded module also takes into account the following additional element
246+
247+
- The obstacles' current lane and position.
248+
- The road shoulder with reference to the direction to avoid.
249+
- Note: Lane direction is disregarded.
250+
251+
These elements are used to compute the distance from the object to the road's shoulder (`(class ObjectData.to_road_shoulder_distance)`).
252+
253+
![fig1](./image/obstacle_to_road_shoulder_distance.png)
254+
255+
##### Computing shift length
256+
257+
To compute the shift length, in addition to the vehicle's width and the parameterized `lateral_collision_margin`, the upgraded feature also adds two new parameters; `lateral_collision_safety_buffer` and `road_shoulder_safety_margin`.
258+
259+
- The `lateral_collision_safety_buffer` parameter is used to set a safety gap that will act as the final line of defense when computing avoidance path.
260+
- The rationale behind having this parameter is that the parameter `lateral_collision_margin` might be changed according to the situation for various reasons. Therefore, `lateral_collision_safety_buffer` will act as the final line of defense in case of the usage of `lateral_collision_margin` fails.
261+
- It is recommended to set the value to more than half of the ego vehicle's width.
262+
- The `road_shoulder_safety_margin` will prevent the module from generating a path that might cause the vehicle to go too near the road shoulder.
263+
264+
![fig1](./image/shift_length_parameters.png)
265+
266+
The shift length is subjected to the following constraints.
267+
268+
<!-- spell-checker:disable -->
269+
270+
$$
271+
\text{shift_length}=\begin{cases}d_{lcsb}+d_{lcm}+\frac{1}{2}(W_{ego})&\text{if}&(d_{lcsb}+d_{lcm}+W_{ego}+d_{rssm})\lt d_{trsd}\\0 &\textrm{if}&\left(d_{lcsb}+d_{lcm}+W_{ego}+d_{rssm}\right)\geq d_{trsd}\end{cases}
272+
$$
273+
274+
where
275+
276+
- <img src="https://latex.codecogs.com/svg.latex?\inline&space;\large&space;d_{lcsb}" title="\large d_{lcsb}" /> = `lateral_collision_safety_buffer`
277+
- <img src="https://latex.codecogs.com/svg.latex?\inline&space;\large&space;d_{lcm}" title="\large d_{lcm}" /> = `lateral_collision_margin`
278+
- <img src="https://latex.codecogs.com/svg.latex?\inline&space;\large&space;W_{ego}" title="\large d_{W_{ego}}" /> = ego vehicle's width
279+
- <img src="https://latex.codecogs.com/svg.latex?\inline&space;\large&space;d_{rssm}" title="\large d_{rssm}" /> = `road_shoulder_safety_margin`
280+
- <img src="https://latex.codecogs.com/svg.latex?\inline&space;\large&space;d_{trsd}" title="\large d_{trsm}" /> = `(class ObjectData).to_road_shoulder_distance`
281+
282+
```plantuml
283+
@startuml
284+
skinparam monochrome true
285+
skinparam defaultTextAlignment center
286+
skinparam noteTextAlignment left
287+
288+
title avoidance path planning
289+
start
290+
partition calcAvoidanceTargetObjects() {
291+
:calcOverhangDistance;
292+
note right
293+
- get overhang_pose
294+
end note
295+
296+
:getClosestLaneletWithinRoute;
297+
note right
298+
- obtain overhang_lanelet
299+
end note
300+
301+
if(Is overhang_lanelet.id() exist?) then (no)
302+
stop
303+
else (\n yes)
304+
305+
if(isOnRight(obstacle)?) then (yes)
306+
partition getLeftMostLineString() {
307+
repeat
308+
repeat
309+
:getLeftLanelet;
310+
note left
311+
Check both
312+
- lane-changeable lane
313+
- non lane-changeable lane
314+
end note
315+
repeat while (Same direction Lanelet exist?) is (yes) not (no)
316+
:getLeftOppositeLanelet;
317+
repeat while (Opposite direction Lanelet exist?) is (yes) not (no)
318+
}
319+
:compute\n(class ObjectData).to_road_shoulder_distance;
320+
note left
321+
distance from overhang_pose
322+
to left most linestring
323+
end note
324+
else(\n no)
325+
partition getrightMostLineString() {
326+
repeat
327+
repeat
328+
:getRightLanelet;
329+
note right
330+
Check both
331+
- lane-changeable lane
332+
- non lane-changeable lane
333+
end note
334+
repeat while (Same direction Lanelet exist?) is (yes) not (no)
335+
:getRightOppositeLanelet;
336+
repeat while (Opposite direction Lanelet exist?) is (yes) not (no)
337+
}
338+
:compute\n(class ObjectData).to_road_shoulder_distance;
339+
note right
340+
distance from overhang_pose
341+
to right most linestring
342+
end note
343+
endif
344+
endif
345+
}
346+
347+
partition calcRawShiftPointsFromObjects() {
348+
:compute max_allowable_lateral_distance;
349+
note right
350+
The sum of
351+
- lat_collision_safety_buffer
352+
- lat_collision_margin
353+
- vehicle_width
354+
end note
355+
:compute max_shift_length;
356+
note right
357+
subtract
358+
- road_shoulder_safety_margin
359+
- 0.5 x vehicle_width
360+
from (class ObjectData).to_road_shoulder_margin
361+
end note
362+
if(isOnRight(object)?) then (yes)
363+
if((class ObjectData).to_road_shoulder_distance \n\l>\l\n max_allowable_lateral_distance ?) then (yes)
364+
:max_left_shift_limit = max_shift_length;
365+
else (\n No)
366+
:max_left_shift_limit = 0.0;
367+
endif
368+
else (\n No)
369+
if((class ObjectData).to_road_shoulder_distance \n\l>\l\n max_allowable_lateral_distance ?) then (yes)
370+
:max_right_shift_limit = -max_shift_length;
371+
else (\n No)
372+
:max_right_shift_limit = 0.0;
373+
endif
374+
endif
375+
:compute shift length;
376+
}
377+
stop
378+
@enduml
379+
```
380+
381+
<!-- spell-checker:enable -->
382+
241383
#### How to keep the consistency of the planning
242384

243385
TODO
@@ -250,7 +392,8 @@ TODO
250392
| :----------------------------------------- | :----- | :----- | :---------------------------------------------------------------------------------------------------------- | :------------ |
251393
| resample_interval_for_planning | [m] | double | Path resample interval for avoidance planning path. | 0.3 |
252394
| resample_interval_for_output | [m] | double | Path resample interval for output path. Too short interval increases computational cost for latter modules. | 3.0 |
253-
| lateral_collision_margin | [m] | double | The lateral distance between ego and avoidance targets. | 2.0 |
395+
| lateral_collision_margin | [m] | double | The lateral distance between ego and avoidance targets. | 1.5 |
396+
| lateral_collision_safety_buffer | [m] | double | Creates an additional gap that will prevent the vehicle from getting to near to the obstacle | 0.5 |
254397
| longitudinal_collision_margin_min_distance | [m] | double | when complete avoidance motion, there is a distance margin with the object for longitudinal direction. | 0.0 |
255398
| longitudinal_collision_margin_time | [s] | double | when complete avoidance motion, there is a time margin with the object for longitudinal direction. | 0.0 |
256399
| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 1.0 |
@@ -262,6 +405,7 @@ TODO
262405
| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 |
263406
| max_right_shift_length | [m] | double | Maximum shift length for right direction | 5.0 |
264407
| max_left_shift_length | [m] | double | Maximum shift length for left direction | 5.0 |
408+
| road_shoulder_safety_margin | [m] | double | Prevents the generated path to come too close to the road shoulders. | 0.5 |
265409

266410
### Speed limit modification
267411

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
# Design limitation
2+
3+
The document describes the limitations that are currently present in the `behavior_path_planner` module.
4+
5+
The following items (but not limited to) fall in the scope of limitation:
6+
7+
- limitations due to the third-party API design and requirement
8+
- limitations due to any shortcoming out of the developer's control.
9+
10+
## Limitation: Multiple connected opposite lanes require Linestring with shared ID
11+
12+
To fully utilize the `Lanelet2`'s [API](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_core/doc/LaneletPrimitives.md#lanelet), the design of the vector map (`.osm`) needs to follow all the criteria described in `Lanelet2` documentation. Specifically, in the case of 2 or more lanes, the Linestrings that divide the current lane with the opposite/adjacent lane need to have a matching `Linestring ID`. Assume the following **ideal case**.
13+
14+
![limitation01-01-ideal-case1](./image/limitations/limitation01-01.png)
15+
16+
In the image, `Linestring ID51` is shared by `Lanelet A` and `Lanelet B`. Hence we can directly use the available `left`, `adjacentLeft`, `right`, `adjacentRight` and `findUsages` method within `Lanelet2`'s API to directly query the direction and opposite lane availability.
17+
18+
```cpp
19+
const auto right_lane = routing_graph_ptr_->right(lanelet);
20+
const auto adjacent_right_lane = routing_graph_ptr_->adjacentRight(lanelet);
21+
const auto opposite_right_lane = lanelet_map_ptr_->laneletLayer.findUsages(lanelet.rightBound().invert());
22+
```
23+
24+
The following images show the situation where **these API does not work directly**. This means that we cannot use them straight away, and several assumptions and logical instruction are needed to make these APIs work.
25+
26+
![limitation01-02-non-work](./image/limitations/limitation01-02-not-work.png)
27+
28+
In this example (multiple linestring issues), `Lanelet C` contains `Linestring ID61` and `ID62`, while `Lanelet D` contains `Linestring ID63` and `ID 64`. Although the `Linestring ID62` and `ID64` have identical point IDs and seem visually connected, the API will treat these Linestring as though they are separated. When it searches for any `Lanelet` that is connected via `Linestring ID62`, it will return `NULL`, since `ID62` only connects to `Lanelet C` and not other `Lanelet`.
29+
30+
Although, in this case, it is possible to forcefully search the lanelet availability by checking the lanelet that contains the points, using`getLaneletFromPoint` method. But, the implementation requires complex rules for it to work. Take the following images as an example.
31+
32+
![limitation01-03-not-equal-length](./image/limitations/limitation01-03-not-equal-length.png)
33+
34+
Assume `Object X` is in `Lanelet F`. We can forcefully search `Lanelet E` via `Point 7`, and it will work if `Point 7` is utilized by **only 2 lanelet**. However, the complexity increases when we want to start searching for the **direction** of the opposite lane. We can infer the direction of the lanelet by using mathematical operations (dot product of vector `V_ID72` (`Point 6` minus `Point 9`), and `V_ID74` (`Point 7` minus `Point 8`). But, notice that we did not use Point 7 in V_ID72. This is because searching it requires an iteration, adding additional non-beneficial computation.
35+
36+
Suppose the points are used by **more than 2 lanelets**. In that case, we have to find the differences for all lanelet, and the result might be undefined. The reason is that the differences between the coordinates do not reflect the actual **shape** of the lanelet. The following image demonstrates this point.
37+
38+
![equal-length-but-non-identical-shape](./image/limitations/limitation01-04-equal-length.png)
39+
40+
![points-shared-more-than-one](./image/limitations/limitation01-04-not-equal.png)
41+
42+
There are many other available solutions to try. However, further attempt to solve this might cause issues in the future, especially for maintaining or scaling up the software.
43+
44+
In conclusion, the multiple Linestring issues will not be supported. Covering these scenarios might give the user an "everything is possible" impression. This is dangerous since any attempt to create a non-standardized vector map is not compliant with safety regulations.
45+
46+
## Limitation: Avoidance at Corners and Intersections
47+
48+
Currently, the implementation doesn't cover avoidance at corners and intersections. The reason is similar to here. However, this case can still be supported in the future (assuming the vector map is defined correctly).
49+
50+
![limitation-at-the-intersections](./image/limitations/limitation-intersection.png)
51+
52+
![limitation-at-the-corner](./image/limitations/limitation-corner.png)

planning/behavior_path_planner/config/avoidance/avoidance.param.yaml

+8-2
Original file line numberDiff line numberDiff line change
@@ -7,11 +7,15 @@
77
detection_area_right_expand_dist: 0.0
88
detection_area_left_expand_dist: 1.0
99

10+
enable_avoidance_over_same_direction: true
11+
enable_avoidance_over_opposite_direction: true
12+
1013
threshold_distance_object_is_on_center: 1.0 # [m]
1114
threshold_speed_object_is_stopped: 1.0 # [m/s]
1215
object_check_forward_distance: 150.0 # [m]
1316
object_check_backward_distance: 2.0 # [m]
14-
lateral_collision_margin: 2.0 # [m]
17+
lateral_collision_margin: 1.0 # [m]
18+
lateral_collision_safety_buffer: 0.7 # [m]
1519

1620
prepare_time: 2.0 # [s]
1721
min_prepare_distance: 1.0 # [m]
@@ -20,6 +24,8 @@
2024
min_nominal_avoidance_speed: 7.0 # [m/s]
2125
min_sharp_avoidance_speed: 1.0 # [m/s]
2226

27+
road_shoulder_safety_margin: 0.5 # [m]
28+
2329
max_right_shift_length: 5.0
2430
max_left_shift_length: 5.0
2531

@@ -30,7 +36,7 @@
3036

3137
# For prevention of large acceleration while avoidance
3238
min_avoidance_speed_for_acc_prevention: 3.0 # [m/s]
33-
max_avoidance_acceleration: 0.5 # [m/ss]
39+
max_avoidance_acceleration: 0.5 # [m/s2]
3440

3541
# for debug
3642
publish_debug_marker: false
Loading
Loading
Loading
Loading
Loading
Loading
Loading
Loading
Loading
Loading

planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ class AvoidanceModule : public SceneModuleInterface
135135

136136
// -- path generation --
137137
ShiftedPath generateAvoidancePath(PathShifter & shifter) const;
138-
void generateExtendedDrivableArea(ShiftedPath * shifted_path, double margin) const;
138+
void generateExtendedDrivableArea(ShiftedPath * shifted_path) const;
139139

140140
// -- velocity planning --
141141
void modifyPathVelocityToPreventAccelerationOnAvoidance(ShiftedPath & shifted_path) const;

planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module_data.hpp

+24
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,13 @@ struct AvoidanceParameters
5252
// lanelet expand length for left side to find avoidance target vehicles
5353
double detection_area_left_expand_dist = 1.0;
5454

55+
// enable avoidance to be perform only in lane with same direction
56+
bool enable_avoidance_over_same_direction{true};
57+
58+
// enable avoidance to be perform in opposite lane direction
59+
// to use this, enable_avoidance_over_same_direction need to be set to true.
60+
bool enable_avoidance_over_opposite_direction{true};
61+
5562
// Vehicles whose distance to the center of the path is
5663
// less than this will not be considered for avoidance.
5764
double threshold_distance_object_is_on_center;
@@ -67,6 +74,9 @@ struct AvoidanceParameters
6774

6875
// we want to keep this lateral margin when avoiding
6976
double lateral_collision_margin;
77+
// a buffer in case lateral_collision_margin is set to 0. Will throw error
78+
// don't ever set this value to 0
79+
double lateral_collision_safety_buffer{0.5};
7080

7181
// when complete avoidance motion, there is a distance margin with the object
7282
// for longitudinal direction
@@ -96,6 +106,10 @@ struct AvoidanceParameters
96106
// distance for avoidance. Need a sharp avoidance path to avoid the object.
97107
double min_sharp_avoidance_speed;
98108

109+
// The margin is configured so that the generated avoidance trajectory does not come near to the
110+
// road shoulder.
111+
double road_shoulder_safety_margin{1.0};
112+
99113
// Even if the obstacle is very large, it will not avoid more than this length for right direction
100114
double max_right_shift_length;
101115

@@ -152,6 +166,15 @@ struct ObjectData // avoidance target
152166

153167
// count up when object disappeared. Removed when it exceeds threshold.
154168
int lost_count = 0;
169+
170+
// store the information of the lanelet which the object's overhang is currently occupying
171+
lanelet::ConstLanelet overhang_lanelet;
172+
173+
// the position of the overhang
174+
Pose overhang_pose;
175+
176+
// lateral distance from overhang to the road shoulder
177+
double to_road_shoulder_distance{0.0};
155178
};
156179
using ObjectDataArray = std::vector<ObjectData>;
157180

@@ -242,6 +265,7 @@ struct DebugData
242265
{
243266
std::shared_ptr<lanelet::ConstLanelets> expanded_lanelets;
244267
std::shared_ptr<lanelet::ConstLanelets> current_lanelets;
268+
std::shared_ptr<lanelet::ConstLineStrings3d> farthest_linestring_from_overhang;
245269

246270
AvoidPointArray current_shift_points; // in path shifter
247271
AvoidPointArray new_shift_points; // in path shifter

planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_utils.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,8 @@ void clipByMinStartIdx(const AvoidPointArray & shift_points, PathWithLaneId & pa
4646
double calcDistanceToClosestFootprintPoint(
4747
const PathWithLaneId & path, const PredictedObject & object, const Point & ego_pos);
4848

49-
double calcOverhangDistance(const ObjectData & object_data, const Pose & base_pose);
49+
double calcOverhangDistance(
50+
const ObjectData & object_data, const Pose & base_pose, Point & overhang_pose);
5051

5152
void setEndData(
5253
AvoidPoint & ap, const double length, const geometry_msgs::msg::Pose & end, const size_t end_idx,

planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/debug.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,12 @@ MarkerArray createPoseMarkerArray(
9090
const Pose & pose, const std::string & ns, const int64_t id, const double r, const double g,
9191
const double b);
9292

93+
MarkerArray makeOverhangToRoadShoulderMarkerArray(
94+
const behavior_path_planner::ObjectDataArray & objects);
95+
96+
MarkerArray createOvehangFurthestLineStringMarkerArray(
97+
const lanelet::ConstLineStrings3d & linestrings, const std::string & ns, const double r,
98+
const double g, const double b);
9399
} // namespace marker_utils
94100

95101
std::string toStrInfo(const behavior_path_planner::ShiftPointArray & sp_arr);

0 commit comments

Comments
 (0)