Role#
Obstacles such as walls or parked trucks can obstruct visibility and create “blind spots” in the environment. The occupancy grid generated by the perception modules contains information about unknown space but this is not currently used by the planning modules.
Goal: consider blind spots during velocity planning.
Approach: assume moving obstacles coming out of blind spots and adjust the velocity profile to stop before the collision point with these obstacles.
This node takes the path generated by mission planner and changes its velocity if necessary.
VelocityProfile#
slow down to the velocity that we can stop before possible collision using emergency braking system (EBS) within predictive braking system (PBS) allowed deceleration.
Parameters#
The parameters are described in config/blindspot_safety_planner.yaml
option | Type | Description | Default value |
---|---|---|---|
safety_time_buffer | double | [s] additional time buffer to consider that ego can pass before an obstacle | 0.5 |
use_custom_iterator | bool | [-] to use custom polygon iterator | false |
Filter To Ignore Unnecessary Case#
filter | Type | Description | Default value |
---|---|---|---|
passable_collisions | bool | [-] if true ignore collisions that ego can pass with its current velocity profile BEFORE the obstacle reaches it | false |
lanelets_with_traffic_lights | bool | [-] if true, ignore obstacle coming from lanelets with traffic lights | false |
only_closest_road_collision | bool | [-] if true, only the closest possible collision with a road obstacle is calculated | false |
Public/Private Road Case#
we assume worst case around public/private road blind spot is car darting out into ego vehicle's trajectory
obstacle | Type | Description | Default value |
---|---|---|---|
obstacle_vel | double | [m/s] minimum velocity assumed for blind spot road obstacles | 3.0 |
min_blindspot_size | double | [m/s] default velocity used for blindspot road obstacles if no speed limit is available | 8.0 |
Sidewalk Case#
we assume worst case around sidewalk blind spot is pedestrian darting out into ego vehicle's trajectory
sidewalk | Type | Description | Default value |
---|---|---|---|
obstacle_vel | double | [m/s] assumed velocity for blind spot sidewalk obstacles | 1.6 |
min_blindspot_size | double | [m/s] assumed velocity for blind spot sidewalk obstacles | 5.0 |
enable | bool | [-] if true, areas on each side of the ego trajectory are checked for blind spots | true |
size | double | [m] buffer around the ego trajectory used to build the sidewalk area. | 5.0 |
Crosswalk Case#
we assume worst case around crosswalk blind spot is bicycle darting out into ego vehicle's trajectory
crosswalk | Type | Description | Default value |
---|---|---|---|
obstacle_vel | double | [m/s] assumed velocity for blind spot crosswalk obstacles | 5.0 |
Threshold To Care About Sidewalk#
road_type_velocity_threshold | Type | Description | Default value |
---|---|---|---|
public | double | [m/s] roads with velocity above this value are considered "public" roads. Bellow is considered "private" | 10.0 |
highway | double | [m/s] roads with velocity above this value are considered "highways" | 20.0 |
Debug Info#
debug | Type | Description | Default value |
---|---|---|---|
debug/publish_info | bool | [-] if true, debug markers are published by the node | false |
debug/print_info | bool | [-] if true, print info are out by the node | false |
Implementation Details#
Detecting possible blindspot positions#
We convert the occupancy grid to a GridMap (
) from which we extract the positions of cells with values corresponding to UNKNOWN space. We are only interested in cells adjacent to FREESPACE cells and we separate the resulting blind spot edges based on the type of lanelet they belong to: road or sidewalk.
Detecting collisions (generatePossibleVehicleCollisions()
)#
We are interesting in collisions with the ego trajectory which we represent with a dummy Lanelet object with the trajectory as its centerline (buildTrajectoryLanelet()
). It is mostly used for projecting points on the trajectory and calculate their longitudinal/lateral distance from ego (using lanelet::geometry::toArcCoordinates()
).
With road vehicle (generatePossibleVehicleCollisions()
)#
Possible collisions with other vehicles are detected by creating a polygon from the trajectory Lanelet and checking intersection points with the lanelet (or successive lanelets) of a road blind spot.
The closest intersection point from the blindspot is set as the collision point.
Can be turned on/off with parameter enable_road_obstacles
.
With sidewalk pedestrian/bicycles (generatePossibleBicycleCollisions()
, generatePossibleOtherCollisions()
)#
Possible collisions with pedestrian or bicycles are detected by drawing a straight line between the blind spot position and the ego trajectory.
The point of the trajectory with the shortest line that does not cross an OCCUPIED cell is set as the collision point.
A distinction is made between blindspot points that are outside of any lanelets (other
) and those that are inside non-road lanelets (sidewalk
). These can turned on/off with parameter sidewalk_enable_obstacles
and enable_other_obstacles
.
Collision Filtering (filtercCollisions()
)#
Redundant collisions#
Some collisions can be considered redundant if there exist another collision at the same point, for the same velocity, but where the obstacle is closer to the collision point.