diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md index 93b57ac3a4831..c7f8e4745580f 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -1,4 +1,4 @@ -# Avoidance design +# Avoidance module for static objects This is a rule-based path planning module designed for obstacle avoidance. @@ -20,7 +20,7 @@ This module executes avoidance over lanes, and the decision requires the lane st The following figure shows a simple explanation of the logic for avoidance path generation. First, target objects are picked up, and shift requests are generated for each object. These shift requests are generated by taking into account the lateral jerk required for avoidance (red lines). Then these requests are merged and the shift points are created on the reference path (blue line). Filtering operations are performed on the shift points such as removing unnecessary shift points (yellow line), and finally a smooth avoidance path is generated by combining Clothoid-like curve primitives (green line). -![fig1](./images/avoidance_design.fig1.drawio.svg) +![fig](./images/avoidance_design.fig.drawio.svg) ### Flowchart @@ -168,114 +168,256 @@ stop @enduml ``` -## Overview of algorithm for target object filtering +## Target object filtering -### How to decide the target obstacles +### Overview -The avoidance target should be limited to stationary objects (you should not avoid a vehicle waiting at a traffic light even if it blocks your path). Therefore, target vehicles for avoidance should meet the following specific conditions. +The module uses following conditions to filter avoidance target objects. -- It is in the vicinity of your lane (parametrized) -- It is stopped - - `threshold_speed_object_is_stopped`: parameter that be used for judge the object has stopped or not. - - `threshold_time_object_is_moving`: parameter that be used for chattering prevention. -- It is a specific class. - - User can limit avoidance targets. - - Fo now, avoidance module supports only vehicle. -- It is not being in the center of the route - - This means that the vehicle is parked on the edge of the lane. This prevents the vehicle from avoiding a vehicle waiting at a traffic light in the middle of the lane. However, this is not an appropriate implementation for the purpose. Even if a vehicle is in the center of the lane, it should be avoided if it has its hazard lights on, and this is a point that should be improved in the future as the recognition performance improves. -- Object is not behind ego(default: > -`2.0 m`) or too far(default: < `150.0 m`) and object is not behind the path goal. +| Check condition | Target class | Details | If conditions are not met | +| -------------------------------------------------------------------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------- | +| Is an avoidance target class object? | All | Use can select avoidance target class from config file. | Never avoid it. | +| Is a stopped object? | All | Objects keep higher speed than `th_moving_speed` for longer period of time than `th_moving_time` is judged as moving. | Never avoid it. | +| Is within detection area? | All | The module creates detection area to filter target objects roughly based on lateral margin in config file. (see [here](#width-of-detection-area)) | Never avoid it. | +| Isn't there enough lateral distance between the object and path? | All | - | Never avoid it. | +| Is near the centerline of ego lane? | All | - | It depends on other conditions. | +| Is there a crosswalk near the object? | Pedestrian, Bicycle | The module don't avoid the Pedestrian and Bicycle nearer the crosswalk because the ego should stop in front of it if they're crossing road. (see [here](#for-crosswalk-users)) | Never avoid it. | +| Is the distance between the object and traffic light along the path longer than threshold? | Car, Truck, Bus, Trailer | The module used this condition if there is ambiguity as to whether the vehicle is a parked vehicle or not. | It depends on other conditions. | +| Is the distance between the object and crosswalk light along the path longer than threshold? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | +| Is the stopping time longer than threshold? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | +| Is within intersection? | Car, Truck, Bus, Trailer | The module assumes that there isn't any parked vehicle within intersection. | It depends on other conditions. | +| Is on ego lane? | Car, Truck, Bus, Trailer | - | It depends on other conditions. | +| Is a parked vehicle? | Car, Truck, Bus, Trailer | The module judges whether the vehicle is a parked vehicle based on its lateral offset. (see [here](#judge-if-its-a-parked-vehicle)) | It depends on other conditions. | +| Is merging to ego lane from other lane? | Car, Truck, Bus, Trailer | The module judges the vehicle behavior based on its yaw angle and offset direction. (see [here](#judge-vehicle-behavior)) | It depends on other conditions. | +| Is merging to other lane from ego lane? | Car, Truck, Bus, Trailer | Same as above. | It depends on other conditions. | -![fig1](./images/target_vehicle_selection.svg) +### Common conditions -### Parked-car detection +#### Detection area -Not only the length from the centerline, but also the length from the road shoulder is calculated and used for the filtering process. It calculates the ratio of _the actual length between the the object's center and the center line_ `shift_length` and _the maximum length the object can shift_ `shiftable_length`. +The module generates detection area for target filtering based on following params: + +```yaml + # avoidance is performed for the object type with true + target_object: + ... + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] + ... + # For target object filtering + target_filtering: + ... + # detection area generation parameters + detection_area: + static: false # [-] + min_forward_distance: 50.0 # [m] + max_forward_distance: 150.0 # [m] + backward_distance: 10.0 # [m] +``` + +##### Width of detection area + +1. get the largest lateral margin of all classes (Car, Truck, ...). The margin is sum of `soft_margin` and `hard_margin_for_parked_vehicle`. +2. the detection area width is sum of ego vehicle width and the largest lateral margin. + +##### Longitudinal distance of detection area + +If the parameter `detection_area.static` is set to `true`, the module creates detection area whose longitudinal distance is `max_forward_distance`. + +If the parameter `detection_area.static` is set to `false`, the module creates detection area so that the ego can avoid objects with minimum lateral jerk value. Thus, the longitudinal distance is depends on lateral maximum shift length, lateral jerk constraints and current ego speed. Additionally, it has to consider distance used for prepare phase. + +```c++ +... + const auto max_shift_length = std::max( + std::abs(parameters_->max_right_shift_length), std::abs(parameters_->max_left_shift_length)); + const auto dynamic_distance = + PathShifter::calcLongitudinalDistFromJerk(max_shift_length, getLateralMinJerkLimit(), speed); + + return std::clamp( + 1.5 * dynamic_distance + getNominalPrepareDistance(), + parameters_->object_check_min_forward_distance, + parameters_->object_check_max_forward_distance); +``` + +![fig](./images/target_filter/detection_area.svg) + +### Conditions for non-vehicle type objects + +#### For crosswalk users + +If Pedestrian and Bicycle are closer to crosswalk than threshold 2.0m (hard coded for now), the module judges they're crossing the road and never avoids them. + +![fig2](./images/target_filter/crosswalk.svg) + +### Conditions for vehicle type objects + +#### Judge vehicle behavior + +The module classifies vehicles into following three behavior based on its yaw angle and offset direction. + +```yaml +# params for filtering objects that are in intersection +intersection: + yaw_deviation: 0.349 # [rad] (default 20.0deg) +``` + +| Behavior | Details | Figure | +| --------- | ---------------------------------------------------------------------------------------------------------------- | -------------------------------------------- | +| NONE | If the object's relative yaw angle to lane is less than threshold `yaw_deviation`, it is classified into `NONE`. | ![fig](./images/target_filter/none.png) | +| MERGING | See following flowchart. | ![fig](./images/target_filter/merging.png) | +| DEVIATING | See following flowchart. | ![fig](./images/target_filter/deviating.png) | + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title Judge vehicle behavior +start + +:calculate object relative yaw angle; +if(angle < threshold or angle > PI - threshold) then (yes) +:it is neither MERGING nor DEVIATING. (=NONE); +stop +endif +if(Is the object on right side of ego path?) then (yes) +if(angle < 0.0 and -PI/2 < angle) then (yes) +#FF006C :DEVIATING; +stop +else (no) +if(angle > PI/2) then (yes) +#FF006C :DEVIATING; +stop +else (no) +endif +endif +else (no) +if(angle > 0.0 and PI/2 > angle) then (yes) +#FF006C :DEVIATING; +stop +else (no) +if(angle < -PI/2) then (yes) +#FF006C :DEVIATING; +stop +else (no) +endif +endif +endif +#00FFB1 :MERGING; +stop +@enduml + +``` + +#### Judge if it's a parked vehicle + +Not only the length from the centerline, but also the length from the road shoulder is calculated and used for the filtering process. In this logic, it calculates ratio of **actual shift length** to **shiftable shift length** as follow. If the result is larger than threshold `th_shiftable_ratio`, the module judges the vehicle as a parked vehicle. $$ -l_D = l_a - \frac{width}{2}, \\ -ratio = \frac{l_d}{l_D} +L_{d} = \frac{W_{lane} - W_{obj}}{2}, \\ +ratio = \frac{l_{a}}{L_{d}} $$ -- $l_d$ : actual shift length -- $l_D$ : shiftable length -- $l_a$ : distance between centerline and most left boundary. -- $width$ : object width +- $L_{d}$ : shiftable length. +- $L_{a}$ : actual shift length. +- $W_{lane}$ : lane width. +- $W_{obj}$ : object width. -The closer the object is to the shoulder, the larger the value of $ratio$ (theoretical max value is 1.0), and it compares the value and `object_check_shiftable_ratio` to determine whether the object is a parked-car. If the road has no road shoulders, it uses `object_check_min_road_shoulder_width` as a road shoulder width virtually. +![fig2](./images/target_filter/parked_vehicle.svg) -![fig2](./images/parked-car-detection.svg) +### Target object filtering -### Compensation for detection lost - -In order to prevent chattering of recognition results, once an obstacle is targeted, it is hold for a while even if it disappears. This is effective when recognition is unstable. However, since it will result in over-detection (increase a number of false-positive), it is necessary to adjust parameters according to the recognition accuracy (if `object_last_seen_threshold = 0.0`, the recognition result is 100% trusted). +| Situation | Details | Ego behavior | +| -------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------- | +| Vehicle is within intersection area defined in HDMap. The module ignores vehicle which is following lane or merging to ego lane. | ![fig](./images/target_filter/never_avoid_intersection.png) | Never avoid it. | +| Vehicle is on ego lane. There are adjacent lanes for both side. | ![fig](./images/target_filter/never_avoid_not_edge.png) | Never avoid it. | +| Vehicle is merging to other lane from ego lane. Most part of its footprint is on ego lane. | ![fig](./images/target_filter/never_avoid_deviating.png) | Never avoid it. | +| Vehicle is merging to ego lane from other lane. Most part of its footprint is on ego lane. | ![fig](./images/target_filter/never_avoid_merging.png) | Never avoid it. | +| Vehicle is not a obvious parked vehicle and stopping in front of the crosswalk or traffic light. | ![fig](./images/target_filter/never_avoid_stop_factor.png) | Never avoid it. | +| Vehicle stops on ego lane with pulling over to the side of the road. | ![fig](./images/target_filter/avoid_on_ego_lane.png) | Avoid it immediately. | +| Vehicle stops on adjacent lane. | ![fig](./images/target_filter/avoid_not_on_ego_lane.png) | Avoid it immediately. | +| Vehicle stops on ego lane without pulling over to the side of the road. | ![fig](./images/target_filter/ambiguous_parallel.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | +| Vehicle is merging to ego lane from other lane. | ![fig](./images/target_filter/ambiguous_merging.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | +| Vehicle is merging to other lane from ego lane. | ![fig](./images/target_filter/ambiguous_deviating.png) | Set the parameter `avoidance_for_ambiguous_vehicle.enable` to `true`, the module avoids ambiguous vehicle. | ### Flowchart +There are three main filtering functions `isSatisfiedWithCommonCondition()`, `isSatisfiedWithVehicleCondition()` and `isSatisfiedWithNonVehicleCondition()`. The filtering process is executed according to following flowchart. Additionally, the module checks avoidance necessity in `isNoNeedAvoidanceBehavior()` based on the object pose, ego path and lateral margin in config file. + ```plantuml @startuml skinparam defaultTextAlignment center skinparam noteTextAlignment left -title object filtering flowchart +title Object filtering flowchart start -if(object is satisfied with common target condition ?) then (yes) -if(vehicle can pass by the object without avoidance ?) then (yes) -:return false; +if(isSatisfiedWithCommonCondition()) then (yes) +if(isNoNeedAvoidanceBehavior()) then (yes) +#00FFB1 :IGNORE; stop else (\n no) endif else (\n no) -:return false; +#00FFB1 :IGNORE; stop endif - -if(object is vehicle type ?) then (yes) -if(object is satisfied with vehicle type target condition ?) then (yes) +if(Is vehicle type?) then (yes) +if(isSatisfiedWithVehicleCodition()) then (yes) else (\n no) -:return false; +#00FFB1 :IGNORE; stop endif else (\n no) -if(object is satisfied with non-vehicle type target condition ?) then (yes) +if(isSatisfiedWithNonVehicleCodition()) then (yes) else (\n no) -:return false; +#00FFB1 :IGNORE; stop endif endif - -#FF006C :return true; +#FF006C :TARGET; stop @enduml ``` +#### Common conditions + +At first, the function `isSatisfiedWithCommonCondition()` includes conditions used for all object class. + ```plantuml @startuml skinparam defaultTextAlignment center skinparam noteTextAlignment left -title filtering flow for all types object +title Common filtering flow start partition isSatisfiedWithCommonCondition() { -if(object is avoidance target type ?) then (yes) -if(object is moving more than threshold time ?) then (yes) -:return false; +if(Is object within detection area? (filtering roughly by position.)) then (yes) +if(Is object an avoidance target type?) then (yes) +if(Is moving object?) then (yes) +#00FFB1 :return false; stop else (\n no) -if(object is farther than forward distance threshold ?) then (yes) -:return false; +if(Is object farther than forward distance threshold ?) then (yes) +#00FFB1 :return false; stop else (\n no) -If(object is farther than backward distance threshold ?) then (yes) -:return false; +If(Is object farther than backward distance threshold ?) then (yes) +#00FFB1 :return false; stop else (\n no) endif endif endif else (\n no) -:return false; +#00FFB1 :return false; +stop +endif +else (\n no) +#00FFB1 :return false; stop endif #FF006C :return true; @@ -283,14 +425,26 @@ stop } @enduml + ``` +#### Conditions for vehicle + +Target class: + +- Car +- Truck +- Bus +- Trailer + +As a next step, object is filtered by condition specialized for its class. + ```plantuml @startuml skinparam defaultTextAlignment center skinparam noteTextAlignment left -title filtering flow for vehicle type objects +title Filtering flow for vehicle type objects start partition isSatisfiedWithVehicleCodition() { @@ -298,50 +452,177 @@ if(object is force avoidance target ?) then (yes) #FF006C :return true; stop else (\n no) -if(object is nearer lane centerline than threshold ?) then (yes) -:return false; + +if(isNeverAvoidanceTarget()) then (yes) +#00FFB1 :return false; stop else (\n no) -if(object is on same lane for ego ?) then (yes) -if(object is shifting right or left side road shoulder more than threshold ?) then (yes) + +if(isObviousAvoidanceTarget()) then (yes) #FF006C :return true; stop else (\n no) -:return false; + +if(Is stopping time longher than threshold?) then (no) +#00FFB1 :return false; +stop +else (\n no) + +if(Is object within intersection?) then (yes) +if(Is object deviating from ego lane?) then (yes) +#FF006C :return true(ambiguous); stop +else (\n no) endif else (\n no) -if(object is in intersection ?) then (no) -#FF006C :return true; + +if(Is object merging to ego lane?) then (yes) +#FF006C :return true(ambiguous); stop -else (\n yes) -if(object pose is paralell to ego lane ?) then (no) +else (\n no) +endif + +if(Is object deviating from ego lane?) then (yes) +#FF006C :return true(ambiguous); +stop +else (\n no) +endif + +if(Is object parallel to ego lane?) then (yes) #FF006C :return true; stop -else (\n yes) -:return false; +else (\n no) +endif + +endif +endif +endif +endif +endif +#00FFB1 :return false; stop +} + +@enduml + +``` + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title Filter vehicle which is obviously not an avoidance target +start + +partition isNeverAvoidanceTarget() { +if(Is object within intersection?) then (yes) + +if(Is object parallel to ego lane?) then (yes) +#00FFB1 :return true; +stop +else (\n no) endif + +if(Is object merging to ego lane?) then (yes) +#00FFB1 :return true; +stop +else (\n no) endif + +else (\n no) +endif + +if(Is object merging to ego lane?) then (yes) +if(Is overhang distance larger than threshold?) then (yes) +#00FFB1 :return true; +stop +else (\n no) +endif +else (\n no) +endif + +if(Is object deviating from ego lane?) then (yes) +if(Is overhang distance larger than threshold?) then (yes) +#00FFB1 :return true; +stop +else (\n no) +endif +else (\n no) +endif + +if(Is object on ego lane?) then (yes) +if(Is object on edge lane?) then (no) +#00FFB1 :return true; +stop +else (\n no) +endif +else (\n no) +endif + +if(isCloseToStopFactor()) then (yes) +if(Is object on ego lane? AND Isn't object a parked vehile?) then (no) +#00FFB1 :return true; +stop +else (\n no) +endif +else (\n no) +endif + +#FF006C :return false; +stop +} + +@enduml +``` + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title Filter vehicle which is obviously an avoidance target +start + +partition isObviousAvoidanceTarget() { +if(Is object within intersection?) then (yes) +else (\n no) +if(Is object parallel to ego lane? AND Is object a parked vehicle?) then (yes) +#FF006C :return true; +stop +else (\n no) endif + +if(Is object parallel to ego lane? AND Isn't object on ego lane?) then (yes) +#FF006C :return true; +stop +else (\n no) endif endif + +#00FFB1 :return false; +stop } @enduml ``` +#### Conditions for non-vehicle objects + +- Pedestrian +- Bicycle + ```plantuml @startuml skinparam defaultTextAlignment center skinparam noteTextAlignment left -title filtering flow for non-vehicle type objects +title Filtering flow for non-vehicle type objects start partition isSatisfiedWithNonVehicleCodition() { -if(object is nearer crosswalk than threshold ?) then (yes) -:return false; +if(isWithinCrosswalk()) then (yes) +#00FFB1 :return false; stop else (\n no) endif @@ -352,88 +633,117 @@ stop @enduml ``` -## Overview of algorithm for avoidance path generation +## Path generation ### How to prevent shift line chattering that is caused by perception noise -Since object recognition results contain noise related to position ,orientation and boundary size, if the raw object recognition results are used in path generation, the avoidance path will be directly affected by the noise. +Since object recognition result contains noise related to position, orientation and polygon shape, if the module uses the raw object recognition results in path generation, the output path will be directly affected by the noise. Therefore, in order to reduce the influence of the noise, this module generates polygon for each target objects, and the output path is generated based on that. -Therefore, in order to reduce the influence of the noise, avoidance module generate a envelope polygon for the avoidance target that covers it, and the avoidance path should be generated based on that polygon. The envelope polygons are generated so that they are parallel to the reference path and the polygon size is larger than the avoidance target (define by `object_envelope_buffer`). The position and size of the polygon is not updated as long as the avoidance target exists within that polygon. +The envelope polygon is a rectangle box, whose size depends on object's polygon and buffer parameter `envelope_buffer_margin`. Additionally, it is always parallel to reference path. When the module finds target object for the first time, it initializes the polygon. ```yaml -# default value -object_envelope_buffer: 0.3 # [m] + car: + ... + envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER ``` -![fig1](./images/envelope_polygon.svg) +![fig](./images/path_generation/envelope_polygon.png) -![fig1](./images/shift_line_generation.svg) +The module creates one-shot envelope polygon by using latest object pose and raw polygon in every planning cycle. On the other hand, the module envelope polygon information which is created in last planning cycle as well in order to update envelope polygon according to following logic. If the one-shot envelope polygon is not within previous envelope polygon, the module creates new envelope polygon. Otherwise, it keeps previous envelope polygon. By doing this process, the envelope polygon size and pose will converge even if perception output includes noise in object pose or shape. -### Computing Shift Length and Shift Points +![fig](./images/path_generation/polygon_update.png) -The lateral shift length is affected by 4 variables, namely `lateral_collision_safety_buffer`, `lateral_collision_margin`, `vehicle_width` and `overhang_distance`. The equation is as follows +### Relationship between envelope polygon and avoidance path -```C++ -avoid_margin = lateral_collision_margin + lateral_collision_safety_buffer + 0.5 * vehicle_width -max_allowable_lateral_distance = to_road_shoulder_distance - road_shoulder_safety_margin - 0.5 * vehicle_width -if(isOnRight(o)) -{ - shift_length = avoid_margin + overhang_distance -} -else -{ - shift_length = avoid_margin - overhang_distance -} +The avoidance path has two shift section, whose start or end point position depends on envelope polygon. The end point of avoidance shift section and start point of return shift section are fixed based on envelope polygon and the other side edges are dynamically changed based on ego speed, shift length, lateral jerk constraints, etc... + +The lateral positions of the two points are decided so that there can be enough space (=lateral margin) between ego body and the most overhang point of envelope polygon edge points. User can adjust lateral margin with following parameters. + +```yaml + car: + ... + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] ``` -The following figure illustrates these variables(This figure just shows the max value of lateral shift length). +The longitudinal positions depends on envelope polygon, ego vehicle specification and following parameters. The longitudinal distance between avoidance shift section end point and envelope polygon (=front longitudinal buffer) is sum of `front_overhang` defined in `vehicle_info.param.yaml` and `longitudinal_margin` if the parameter `consider_front_overhang` is `true`. If `consider_front_overhang` is `false`, only `longitudinal_margin` is considered. Similarly, the distance between return shift section start point and envelope polygon (=rear longitudinal buffer) is sum of `rear_overhang` and `longitudinal_margin`. -![shift_point_and_its_constraints](./images/avoidance_module-shift_point_and_its_constraints.drawio.png) +```yaml -### Rationale of having safety buffer and safety margin + target_object: + car: + ... + longitudinal_margin: 0.0 # [m] + + ... + avoidance: + ... + longitudinal: + ... + consider_front_overhang: true # [-] + consider_rear_overhang: true # [-] +``` -To compute the shift length, additional parameters that can be tune are `lateral_collision_safety_buffer` and `road_shoulder_safety_margin`. +![fig](./images/path_generation/margin.png) -- 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. - - The rationale behind having this parameter is that the parameter `lateral_collision_margin` might be changing 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. - - It is recommended to set the value to more than half of the ego vehicle's width. -- 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 or adjacent lane dividing line. +### Shift length calculation -![shift_length_parameters](./images/shift_length_parameters.drawio.svg) +The lateral shift length is sum of `overhang_distance`, lateral margin, whose value is set in config file, and the half of ego vehicle width defined in `vehicle_info.param.yaml`. On the other hand, the module limits the shift length depending on the space which the module can use for avoidance maneuver and the parameters `soft_drivable_bound_margin` `hard_drivable_bound_margin`. Basically, the shift length is limited so that the ego doesn't get closer than `soft_drivable_bound_margin` to drivable boundary. But it allows to relax the threshold `soft_drivable_bound_margin` to `hard_drivable_bound_margin` when the road is narrow. -### Generating path only within lanelet boundaries +![fig](./images/path_generation/lateral.png) -The shift length is set as a constant value before the feature is implemented. 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 module also takes into account the following additional element +Usable lane for avoidance module can be selected by config file. -- The obstacles' current lane and position. -- The road shoulder with reference to the direction to avoid. +```yaml + ... + use_adjacent_lane: true + use_opposite_lane: true +``` + +When user set parameter both `use_adjacent_lane` and `use_opposite_lane` to `true`, it is possible to use opposite lane. + +![fig](./images/path_generation/opposite_direction.png) -These elements are used to compute the distance from the object to the road's shoulder (`to_road_shoulder_distance`). The parameters `use_adjacent_lane` and `use_opposite_lane` allows further configuration of the to `to_road_shoulder_distance`. The following image illustrates the configuration. +When user only set parameter `use_adjacent_lane` to `true`, the module doesn't create path that overlaps opposite lane. -![obstacle_to_road_shoulder_distance](./images/obstacle_to_road_shoulder_distance.drawio.svg) +![fig](./images/path_generation/same_direction.png) -If one of the following conditions is `false`, then the shift point will not be generated. +### Shift line generation -- The distance to shoulder of road is enough +As mentioned above, the end point of avoidance shift path and the start point of return shift path, which are FIXED points, are calculated from envelope polygon. As a next step, the module adjusts the other side points depending on shift length, current ego speed and lateral jerk constrain params defined in config file. -```C++ -avoid_margin = lateral_collision_margin + lateral_collision_safety_buffer + 0.5 * vehicle_width -avoid_margin <= (to_road_shoulder_distance - 0.5 * vehicle_width - road_shoulder_safety_margin) +Since the two points are always on centerline of ego lane, the module only calculates longitudinal distance between shift start and end point based on following function. This function is defined in path shifter library, so please see [this](https://github.com/autowarefoundation/autoware.universe/blob/main/planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md) page as well. + +```c++ +double PathShifter::calcLongitudinalDistFromJerk( + const double lateral, const double jerk, const double velocity) +{ + const double j = std::abs(jerk); + const double l = std::abs(lateral); + const double v = std::abs(velocity); + if (j < 1.0e-8) { + return 1.0e10; + } + return 4.0 * std::pow(0.5 * l / j, 1.0 / 3.0) * v; +} ``` -- The obstacle intrudes into the current driving path. +We call the line which connects shift start and end point `shift_line`, whom the avoidance path is generated from with spline completion. - - when the object is on right of the path +The start point of avoidance has another longitudinal constraint. In order to keep turning on the blinker for few seconds before starting avoidance maneuver, the avoidance start point must be further than the value (we call the distance `prepare_length`.) depending on ego speed from ego position. - ```C++ - -overhang_dist<(lateral_collision_margin + lateral_collision_safety_buffer + 0.5 * vehicle_width) - ``` +```yaml +longitudinal: + min_prepare_time: 1.0 # [s] + max_prepare_time: 2.0 # [s] + min_prepare_distance: 1.0 # [m] +``` - - when the object is on left of the path +The `prepare_length` is calculated as the product of ego speed and `max_prepare_time`. (When the ego speed is zero, `min_prepare_distance` is used.) - ```C++ - overhang_dist<(lateral_collision_margin + lateral_collision_safety_buffer + 0.5 * vehicle_width) - ``` +![fig](./images/path_generation/shift_line.png) ## Details of algorithm for avoidance path generation @@ -565,7 +875,7 @@ To solve that, this module provides a parameter for the minimum avoidance speed, - If the ego vehicle speed is lower than "nominal" minimum speed, use the minimum speed in the calculation of the jerk. - If the ego vehicle speed is lower than "sharp" minimum speed and a nominal lateral jerk is not enough for avoidance (the case where the ego vehicle is stopped close to the obstacle), use the "sharp" minimum speed in the calculation of the jerk (it should be lower than "nominal" speed). -![fig1](./images/how_to_decide_path_shape_one_object.drawio.svg) +![fig](./images/how_to_decide_path_shape_one_object.drawio.svg) #### Multiple obstacle case (one direction) @@ -575,13 +885,13 @@ Generate shift points for multiple obstacles. All of them are merged to generate For the details of the shift point filtering, see [filtering for shift points](#filtering-for-shift-points). -![fig1](./images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg) +![fig](./images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg) #### Multiple obstacle case (both direction) Generate shift points for multiple obstacles. All of them are merged to generate new shift points. If there are areas where the desired shifts conflict in different directions, the sum of the maximum shift amounts of these areas is used as the final shift amount. The rest of the process is the same as in the case of one direction. -![fig1](./images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg) +![fig](./images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg) #### Filtering for shift points @@ -594,37 +904,36 @@ The shift points are modified by a filtering process in order to get the expecte ## Other features +### Compensation for detection lost + +In order to prevent chattering of recognition results, once an obstacle is targeted, it is hold for a while even if it disappears. This is effective when recognition is unstable. However, since it will result in over-detection (increase a number of false-positive), it is necessary to adjust parameters according to the recognition accuracy (if `object_last_seen_threshold = 0.0`, the recognition result is 100% trusted). + ### Drivable area expansion -This module has following parameters that sets which areas the path may extend into when generating an avoidance path. +This module supports drivable area expansion for following polygons defined in HDMap. + +- intersection area +- hatched road marking +- freespace area + +Please set the flags to `true` when user wants to make it possible to use those areas in avoidance maneuver. ```yaml # drivable area setting use_adjacent_lane: true use_opposite_lane: true -use_intersection_areas: false -use_hatched_road_markings: false +use_intersection_areas: true +use_hatched_road_markings: true +use_freespace_areas: true ``` -#### adjacent lane - -![fig1](./images/use_adjacent_lane.svg) - -#### opposite lane - -![fig1](./images/use_opposite_lane.svg) - -#### intersection areas - -The intersection area is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) - -![fig1](./images/use_intersection_areas.svg) - -#### hatched road markings - -The hatched road marking is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#hatched-road-markings-area) - -![fig1](./images/use_hatched_road_markings.svg) +| | | | +| --------------------- | ---------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| adjacent lane | ![fig](./images/advanced/avoidance_same_direction.png) | | +| opposite lane | ![fig](./images/advanced/avoidance_opposite_direction.png) | | +| intersection area | ![fig](./images/advanced/avoidance_intersection.png) | The intersection area is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) | +| hatched road markings | ![fig](./images/advanced/avoidance_zebra.png) | The hatched road marking is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#hatched-road-markings-area) | +| freespace area | ![fig](./images/advanced/avoidance_freespace.png) | The freespace area is defined on Lanelet map. (unstable) | ### Safety check @@ -647,11 +956,11 @@ safety_check_backward_distance: 50.0 # [m] safety_check_accel_for_rss: 2.5 # [m/ss] ``` -![fig1](./images/safety_check_flowchart.svg) +![fig](./images/safety_check_flowchart.svg) `safety_check_backward_distance` is the parameter related to the safety check area. The module checks a collision risk for all vehicle that is within shift side lane and between object `object_check_forward_distance` ahead and `safety_check_backward_distance` behind. -![fig1](./images/safety_check_step_1.svg) +![fig](./images/safety_check_step_1.svg) **NOTE**: Even if a part of an object polygon overlaps the detection area, if the center of gravity of the object does not exist on the lane, the vehicle is excluded from the safety check target. @@ -659,11 +968,11 @@ safety_check_accel_for_rss: 2.5 # [m/ss] Judge the risk of collision based on ego future position and object prediction path. The module calculates Ego's future position in the time horizon (`safety_check_time_horizon`), and use object's prediction path as object future position. -![fig1](./images/safety_check_step_2.svg) +![fig](./images/safety_check_step_2.svg) After calculating the future position of Ego and object, the module calculates the lateral/longitudinal deviation of Ego and the object. The module also calculates the lateral/longitudinal margin necessary to determine that it is safe to execute avoidance maneuver, and if both the lateral and longitudinal distances are less than the margins, it determines that there is a risk of a collision at that time. -![fig1](./images/safety_check_margin.svg) +![fig](./images/safety_check_margin.svg) The value of the longitudinal margin is calculated based on Responsibility-Sensitive Safety theory ([RSS](https://newsroom.intel.com/articles/rss-explained-five-rules-autonomous-vehicle-safety/#gs.ljzofv)). The `safety_check_idling_time` represents $T_{idle}$, and `safety_check_accel_for_rss` represents $a_{max}$. @@ -673,7 +982,7 @@ $$ The lateral margin is changeable based on ego longitudinal velocity. If the vehicle is driving at a high speed, the lateral margin should be larger, and if the vehicle is driving at a low speed, the value of the lateral margin should be set to a smaller value. Thus, the lateral margin for each vehicle speed is set as a parameter, and the module determines the lateral margin from the current vehicle speed as shown in the following figure. -![fig1](./images/dynamic_lateral_margin.svg) +![fig](./images/dynamic_lateral_margin.svg) ```yaml target_velocity_matrix: @@ -695,7 +1004,7 @@ If an avoidance path can be generated and it is determined that avoidance maneuv yield_velocity: 2.78 # [m/s] ``` -![fig1](./images/yield_maneuver.svg) +![fig](./images/yield_maneuver.svg) **NOTE**: In yield maneuver, the vehicle decelerates target velocity under constraints. @@ -736,9 +1045,9 @@ $$ SHIFT_{current} > L_{threshold} $$ -![fig1](./images/yield_limitation.svg) +![fig](./images/yield_limitation.svg) -![fig1](./images/yield_maneuver_flowchart.svg) +![fig](./images/yield_maneuver_flowchart.svg) --- @@ -767,7 +1076,7 @@ The avoidance specific parameter configuration file can be located at `src/autow - **Planning on the intersection** - If it is known that the ego vehicle is going to stop in the middle of avoidance execution (for example, at a red traffic light), sometimes the avoidance should not be executed until the vehicle is ready to move. This is because it is impossible to predict how the environment will change during the stop. This is especially important at intersections. -![fig1](./images/intersection_problem.drawio.svg) +![fig](./images/intersection_problem.drawio.svg) - **Safety Check** @@ -795,7 +1104,7 @@ The avoidance specific parameter configuration file can be located at `src/autow Developers can see what is going on in each process by visualizing all the avoidance planning process outputs. The example includes target vehicles, shift points for each object, shift points after each filtering process, etc. -![fig1](./images/avoidance-debug-marker.png) +![fig](./images/avoidance-debug-marker.png) To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner avoidance.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `static_obstacle_avoidance.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance` in `rviz2`. diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_freespace.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_freespace.png new file mode 100644 index 0000000000000..f6f0cdf72f495 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_freespace.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_intersection.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_intersection.png new file mode 100644 index 0000000000000..13a06f01ac6de Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_intersection.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_opposite_direction.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_opposite_direction.png new file mode 100644 index 0000000000000..0f17ea914abed Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_opposite_direction.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_same_direction.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_same_direction.png new file mode 100644 index 0000000000000..a2247d8cda185 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_same_direction.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_zebra.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_zebra.png new file mode 100644 index 0000000000000..b129ddeacff77 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/advanced/avoidance_zebra.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/envelope_polygon.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/envelope_polygon.png new file mode 100644 index 0000000000000..5a627ab740cab Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/envelope_polygon.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png new file mode 100644 index 0000000000000..8d8512f042922 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/margin.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/margin.png new file mode 100644 index 0000000000000..8920a7be56ff9 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/margin.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/opposite_direction.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/opposite_direction.png new file mode 100644 index 0000000000000..43c72e1d5abd8 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/opposite_direction.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/polygon_update.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/polygon_update.png new file mode 100644 index 0000000000000..1503fe58382a5 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/polygon_update.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/same_direction.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/same_direction.png new file mode 100644 index 0000000000000..acf1134c85c5c Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/same_direction.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/shift_line.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/shift_line.png new file mode 100644 index 0000000000000..9700a6ea4cb97 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/shift_line.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_deviating.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_deviating.png new file mode 100644 index 0000000000000..437e5129fc6cf Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_deviating.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_merging.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_merging.png new file mode 100644 index 0000000000000..d7263228a0e38 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_merging.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_parallel.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_parallel.png new file mode 100644 index 0000000000000..0da7af1fdd138 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/ambiguous_parallel.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/avoid_not_on_ego_lane.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/avoid_not_on_ego_lane.png new file mode 100644 index 0000000000000..f99d26b6c1f25 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/avoid_not_on_ego_lane.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/avoid_on_ego_lane.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/avoid_on_ego_lane.png new file mode 100644 index 0000000000000..9620934857d86 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/avoid_on_ego_lane.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/crosswalk.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/crosswalk.svg new file mode 100644 index 0000000000000..4ecd939897e0a --- /dev/null +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/crosswalk.svg @@ -0,0 +1,148 @@ + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ ignore +
+
+
+
+ ignore +
+
+
+ + + + + + + + + + + +
+
+
+ target +
+
+
+
+ target +
+
+
+ + + + + + + + + + + + + + + + +
+
+
+ ignore +
+
+
+
+ ignore +
+
+
+
+
diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/detection_area.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/detection_area.svg new file mode 100644 index 0000000000000..1390cfed01a04 --- /dev/null +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/detection_area.svg @@ -0,0 +1,272 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ backward_distance +
+
+
+
+ backward_d... +
+
+
+ + + + + + + +
+
+
+ detection area +
+
+
+
+ detection area +
+
+
+ + + + + + + +
+
+
+ forward_distance +
+
+
+
+ forward_di... +
+
+
+ + + + + + + + + + + + +
+
+
+ vehicle_width +
+
+
+
+ vehicle_wi... +
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ target +
+
+
+
+ target +
+
+
+ + + + + + + +
+
+
+ ignore +
+
+
+
+ ignore +
+
+
+ + + + + + + + + + +
+
+
+ target +
+
+
+
+ target +
+
+
+
+
diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/deviating.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/deviating.png new file mode 100644 index 0000000000000..8ccf1f67a685c Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/deviating.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/merging.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/merging.png new file mode 100644 index 0000000000000..e950136f2c3ec Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/merging.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_deviating.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_deviating.png new file mode 100644 index 0000000000000..e635aee9ff74d Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_deviating.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_intersection.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_intersection.png new file mode 100644 index 0000000000000..4f470bc4b4442 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_intersection.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_merging.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_merging.png new file mode 100644 index 0000000000000..6ceb068d3889f Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_merging.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_not_edge.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_not_edge.png new file mode 100644 index 0000000000000..839b704b6c2b7 Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_not_edge.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_stop_factor.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_stop_factor.png new file mode 100644 index 0000000000000..852c2835cb57e Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/never_avoid_stop_factor.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/none.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/none.png new file mode 100644 index 0000000000000..7c94bcf6c6e7c Binary files /dev/null and b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/none.png differ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/parked_vehicle.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/parked_vehicle.svg new file mode 100644 index 0000000000000..e891b1d39ced6 --- /dev/null +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_filter/parked_vehicle.svg @@ -0,0 +1,172 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ shiftable length +
+
+
+
+ shiftable... +
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+ actual shift length +
+
+
+
+ actual shi... +
+
+
+ + + + + + + + + + + + +
+
+
+ vehicle width +
+
+
+
+ vehicle wi... +
+
+
+ + + + + + + + + + + + +
+
+
+ lane width +
+
+
+
+ lane width +
+
+
+
+