Behavior Velocity Planner#
Overview#
behavior_velocity_planner
is a planner that adjust velocity based on the traffic rules.
It loads modules as plugins. Please refer to the links listed below for detail on each module.
- Blind Spot
- Crosswalk
- Walkway
- Detection Area
- Intersection
- MergeFromPrivate
- Stop Line
- Virtual Traffic Light
- Traffic Light
- Occlusion Spot
- No Stopping Area
- Run Out
- Speed Bump
When each module plans velocity, it considers based on base_link
(center of rear-wheel axis) pose.
So for example, in order to stop at a stop line with the vehicles' front on the stop line, it calculates base_link
position from the distance between base_link
to front and modifies path velocity from the base_link
position.
Input topics#
Name | Type | Description |
---|---|---|
~input/path_with_lane_id |
tier4_planning_msgs::msg::PathWithLaneId | path with lane_id |
~input/vector_map |
autoware_map_msgs::msg::LaneletMapBin | vector map |
~input/vehicle_odometry |
nav_msgs::msg::Odometry | vehicle velocity |
~input/dynamic_objects |
autoware_perception_msgs::msg::PredictedObjects | dynamic objects |
~input/no_ground_pointcloud |
sensor_msgs::msg::PointCloud2 | obstacle pointcloud |
~/input/compare_map_filtered_pointcloud |
sensor_msgs::msg::PointCloud2 | obstacle pointcloud filtered by compare map. Note that this is used only when the detection method of run out module is Points. |
~input/traffic_signals |
autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states |
Output topics#
Name | Type | Description |
---|---|---|
~output/path |
autoware_planning_msgs::msg::Path | path to be followed |
~output/stop_reasons |
tier4_planning_msgs::msg::StopReasonArray | reasons that cause the vehicle to stop |
Node parameters#
Parameter | Type | Description |
---|---|---|
launch_modules |
vector<string> | module names to launch |
forward_path_length |
double | forward path length |
backward_path_length |
double | backward path length |
max_accel |
double | (to be a global parameter) max acceleration of the vehicle |
system_delay |
double | (to be a global parameter) delay time until output control command |
delay_response_time |
double | (to be a global parameter) delay time of the vehicle's response to control commands |
Traffic Light Handling in sim/real#
The handling of traffic light information varies depending on the usage. In the below table, the traffic signal topic element for the corresponding lane is denoted as info
, and if info
is not available, it is denoted as null
.
module \ case | info is null |
info is not null |
---|---|---|
intersection_occlusion(is_simulation = * )
|
GO(occlusion is ignored) | intersection_occlusion uses the latest non UNKNOWN observation in the queue up to present.
|
traffic_light(sim, is_simulation = true )
|
GO | traffic_light uses the perceived traffic light information at present directly.
|
traffic_light(real, is_simulation = false )
|
STOP | |
crosswalk with Traffic Light(is_simulation = * )
|
default |
|
map_based_prediction(is_simulation = * )
|
default | If a pedestrian traffic light is
|