Skip to content

Files

Latest commit

971af2a · Feb 22, 2024

History

History
341 lines (277 loc) · 13.9 KB

File metadata and controls

341 lines (277 loc) · 13.9 KB

Occlusion Spot

Role

This module plans safe velocity to slow down before reaching collision point that hidden object is darting out from occlusion spot where driver can't see clearly because of obstacles.

brief

Activation Timing

This module is activated if launch_occlusion_spot becomes true. To make pedestrian first zone map tag is one of the TODOs.

Limitation and TODOs

This module is prototype implementation to care occlusion spot. To solve the excessive deceleration due to false positive of the perception, the logic of detection method can be selectable. This point has not been discussed in detail and needs to be improved.

  • Make occupancy grid for planning.
  • Make map tag for occlusion spot.
  • About the best safe motion.

TODOs are written in each Inner-workings / Algorithms (see the description below).

Inner-workings / Algorithms

Logics Working

There are several types of occlusions, such as "occlusions generated by parked vehicles" and "occlusions caused by obstructions". In situations such as driving on road with obstacles, where people jump out of the way frequently, all possible occlusion spots must be taken into account. This module considers all occlusion spots calculated from the occupancy grid, but it is not reasonable to take into account all occlusion spots for example, people jumping out from behind a guardrail, or behind cruising vehicle. Therefore currently detection area will be limited to to use predicted object information.

Note that this decision logic is still under development and needs to be improved.

DetectionArea Polygon

This module considers TTV from pedestrian velocity and lateral distance to occlusion spot. TTC is calculated from ego velocity and acceleration and longitudinal distance until collision point using motion velocity smoother. To compute fast this module only consider occlusion spot whose TTV is less than TTC and only consider area within "max lateral distance".

brief

Occlusion Spot Occupancy Grid Base

This module considers any occlusion spot around ego path computed from the occupancy grid. Due to the computational cost occupancy grid is not high resolution and this will make occupancy grid noisy so this module add information of occupancy to occupancy grid map.

TODO: consider hight of obstacle point cloud to generate occupancy grid.

Collision Free Judgement

obstacle that can run out from occlusion should have free space until intersection from ego vehicle

brief

Partition Lanelet

By using lanelet information of "guard_rail", "fence", "wall" tag, it's possible to remove unwanted occlusion spot.

By using static object information, it is possible to make occupancy grid more accurate.

To make occupancy grid for planning is one of the TODOs.

brief

Possible Collision

obstacle that can run out from occlusion is interrupted by moving vehicle.

brief

About safe motion

brief

The Concept of Safe Velocity and Margin

The safe slowdown velocity is calculated from the below parameters of ego emergency braking system and time to collision. Below calculation is included but change velocity dynamically is not recommended for planner.

  • jerk limit[m/s^3]

  • deceleration limit[m/s2]

  • delay response time[s]

  • time to collision of pedestrian[s] with these parameters we can briefly define safe motion before occlusion spot for ideal environment.

    occupancy_grid

This module defines safe margin to consider ego distance to stop and collision path point geometrically. While ego is cruising from safe margin to collision path point, ego vehicle keeps the same velocity as occlusion spot safe velocity.

brief

Note: This logic assumes high-precision vehicle speed tracking and margin for decel point might not be the best solution, and override with manual driver is considered if pedestrian really run out from occlusion spot.

TODO: consider one of the best choices

  1. stop in front of occlusion spot
  2. insert 1km/h velocity in front of occlusion spot
  3. slowdown this way
  4. etc... .
Maximum Slowdown Velocity

The maximum slowdown velocity is calculated from the below parameters of ego current velocity and acceleration with maximum slowdown jerk and maximum slowdown acceleration in order not to slowdown too much.

  • j m a x slowdown jerk limit[m/s^3]
  • a m a x slowdown deceleration limit[m/s2]
  • v 0 current velocity[m/s]
  • a 0 current acceleration[m/s]

brief

Module Parameters

Parameter Type Description
pedestrian_vel double [m/s] maximum velocity assumed pedestrian coming out from occlusion point.
pedestrian_radius double [m] assumed pedestrian radius which fits in occlusion spot.
Parameter Type Description
use_object_info bool [-] whether to reflect object info to occupancy grid map or not.
use_partition_lanelet bool [-] whether to use partition lanelet map data.
Parameter /debug Type Description
is_show_occlusion bool [-] whether to show occlusion point markers.
is_show_cv_window bool [-] whether to show open_cv debug window.
is_show_processing_time bool [-] whether to show processing time.
Parameter /threshold Type Description
detection_area_length double [m] the length of path to consider occlusion spot
stuck_vehicle_vel double [m/s] velocity below this value is assumed to stop
lateral_distance double [m] maximum lateral distance to consider hidden collision
Parameter /motion Type Description
safety_ratio double [-] safety ratio for jerk and acceleration
max_slow_down_jerk double [m/s^3] jerk for safe brake
max_slow_down_accel double [m/s^2] deceleration for safe brake
non_effective_jerk double [m/s^3] weak jerk for velocity planning.
non_effective_acceleration double [m/s^2] weak deceleration for velocity planning.
min_allowed_velocity double [m/s] minimum velocity allowed
safe_margin double [m] maximum error to stop with emergency braking system.
Parameter /detection_area Type Description
min_occlusion_spot_size double [m] the length of path to consider occlusion spot
slice_length double [m] the distance of divided detection area
max_lateral_distance double [m] buffer around the ego path used to build the detection_area area.
Parameter /grid Type Description
free_space_max double [-] maximum value of a free space cell in the occupancy grid
occupied_min double [-] buffer around the ego path used to build the detection_area area.

Flowchart

Rough overview of the whole process
@startuml
title modifyPathVelocity (Occupancy/PredictedObject)
start

partition process_path {
:clip path by length;
:interpolate path;
note right
  using spline interpolation and interpolate (x,y,z,v)
end note
:calc closest path point from ego;
}

partition process_sensor_data {
if (road type is PredictedObject) then (yes)
  :preprocess dynamic object;
else if (road type is Occupancy) then (yes)
  :preprocess occupancy grid map info;
else (no)
  stop
endif
}
:calculate offset from start to ego;
partition generate_detection_area_polygon {
:convert path to path lanelet;
:generate left/right slice of polygon that starts from path start;
:generate interpolated polygon created from ego TTC and lateral distance that pedestrian can reach within ego TTC.;
}
partition find_possible_collision {
:generate possible collision;
:calculate collision path point and intersection point;
note right
  - occlusion spot is calculated by the longitudinally closest point of unknown cells.
  - intersection point is where ego front bumper and the darting object will crash.
  - collision path point is calculated by arc coordinate consider ego vehicle's geometry.
  - safe velocity and safe margin is calculated from performance of ego emergency braking system.
end note
:calculate safe velocity and safe margin for possible collision;
note right
  - safe velocity and safe margin is calculated from performance of ego emergency braking system.
end note
}
partition process_possible_collision {
:filter possible collision by road type;
note right
filter by target road type start and end pair
end note
:calculate slow down points for possible collision;
note right
calculate original velocity and height for the possible collision
end note
:handle collision offset;
note right
consider offset from path start to ego vehicle for possible collision
end note
:apply safe velocity comparing with allowed velocity;
note right
calculated by
- safe velocity calculated from emergency brake performance.
- maximum allowed deceleration [m/s^2]
- min velocity [m/s] the velocity that is allowed on the road.
- original_velocity [m/s]
set minimum velocity for path point after occlusion spot.
end note
}
stop
@enduml
Detail process for predicted object(not updated)
@startuml
title modifyPathVelocity
start

partition process_path {
:clip path by length;
note right
  100m considering perception range
end note
:interpolate ego path;
:get closest index from ego position in interpolated path;
:extract target road type start/end distance by arc length;
}
partition preprocess_dynamic_object {
:get parked vehicle from dynamic object array;
note right
  target parked vehicle is define as follow .
  - dynamic object's semantic type is "car","bus","track".
  - velocity is below `stuck_vehicle_vel`.
end note
}
:generate_detection_area_polygon;
partition find_possible_collision {
:generate possible collision behind parked vehicle;
note right
  - occlusion spot candidate is stuck vehicle polygon 2 points farther which is closer to ego path.
end note
:calculate collision path point and intersection point;
note right
  - occlusion spot is calculated by stuck vehicle polygon.
  - intersection point is where ego front bumper and darting object will crash.
  - collision path point is calculated by arc coordinate consider ego vehicle's geometry.
end note
:calculate safe velocity and safe margin for possible collision;
note right
  - safe velocity and safe margin is calculated from performance of ego emergency braking system.
end note
}
partition process_possible_collision {
:filter collision by road type;
:calculate slow down points for possible collision;
:handle collision offset;
:apply safe velocity comparing with allowed velocity;
:insert safe velocity to path;
}
stop
@enduml
Detail process for Occupancy grid base
@startuml
title modifyPathVelocity For Occupancy
start

partition process_path {
:clip path by length;
note right
  50m considering occupancy grid range
end note
:interpolate ego path;
:get closest index from ego position in interpolated path;
}
partition occupancy_grid_preprocess {
:convert occupancy grid to image;
note right
  convert from occupancy grid to image to use opencv functions.
end note
:remove noise from occupancy to apply dilate and erode;
note right
  applying dilate and erode is much better and faster than rule base noise reduction.
end note
:quantize image to categorize to free_space,unknown,occupied;
:convert image to occupancy grid;
note right
  convert from occupancy grid to image to use opencv functions.
end note
}
:generate_detection_area_polygon;
partition generate_possible_collision {
:calculate offset from path start to ego;
:generate possible collision from occlusion spot;
note right
  - occlusion spot candidate is N by N size unknown cells.
  - consider occlusion spot in detection area polygon.
end note
:filter occlusion spot by partition lanelets;
note right
  - filter occlusion spot by partition lanelets which prevent pedestrians come out.
end note
:calculate collision path point and intersection point;
note right
  - use pedestrian polygon to judge "collision_free" or not.
end note
:calculate safe velocity and safe margin for possible collision;
note right
  - safe velocity and safe margin is calculated from the performance of ego emergency braking system.
end note
}
partition handle_possible_collision {
:filter collision by road type;
:calculate slow down points for possible collision;
:handle collision offset;
:apply safe velocity comparing with allowed velocity;
:insert safe velocity to path;
}
stop
@enduml