You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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>
Copy file name to clipboardexpand all lines: launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml
Copy file name to clipboardexpand all lines: planning/behavior_path_planner/behavior_path_planner_avoidance-design.md
+145-1
Original file line number
Diff line number
Diff line change
@@ -238,6 +238,148 @@ The shift points are modified by a filtering process in order to get the expecte
238
238
- 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.
239
239
- 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.
240
240
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)`).
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
+

265
+
266
+
The shift length is subjected to the following constraints.
| 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 |
254
397
| longitudinal_collision_margin_min_distance |[m]| double | when complete avoidance motion, there is a distance margin with the object for longitudinal direction. | 0.0 |
255
398
| longitudinal_collision_margin_time |[s]| double | when complete avoidance motion, there is a time margin with the object for longitudinal direction. | 0.0 |
256
399
| 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
262
405
| min_sharp_avoidance_speed |[m/s]| double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 |
263
406
| max_right_shift_length |[m]| double | Maximum shift length for right direction | 5.0 |
264
407
| 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 |
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**.
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.
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.
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.
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.
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).
Copy file name to clipboardexpand all lines: planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module_data.hpp
+24
Original file line number
Diff line number
Diff line change
@@ -52,6 +52,13 @@ struct AvoidanceParameters
52
52
// lanelet expand length for left side to find avoidance target vehicles
53
53
double detection_area_left_expand_dist = 1.0;
54
54
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.
0 commit comments