autoware_scenario_selector
scenario_selector_node
scenario_selector_node
is a node that switches trajectories from each scenario.
Name |
Type |
Description |
~input/lane_driving/trajectory |
autoware_planning_msgs::Trajectory |
trajectory of LaneDriving scenario |
~input/parking/trajectory |
autoware_planning_msgs::Trajectory |
trajectory of Parking scenario |
~input/lanelet_map |
autoware_map_msgs::msg::LaneletMapBin |
|
~input/route |
autoware_planning_msgs::LaneletRoute |
route and goal pose |
~input/odometry |
nav_msgs::Odometry |
for checking whether vehicle is stopped |
is_parking_completed |
bool (implemented as rosparam) |
whether all split trajectory of Parking are published |
Output topics
Name |
Type |
Description |
~output/scenario |
tier4_planning_msgs::Scenario |
current scenario and scenarios to be activated |
~output/trajectory |
autoware_planning_msgs::Trajectory |
trajectory to be followed |
Output TFs
None
How to launch
- Write your remapping info in
scenario_selector.launch
or add args when executing roslaunch
roslaunch autoware_scenario_selector scenario_selector.launch
- If you would like to use only a single scenario,
roslaunch autoware_scenario_selector dummy_scenario_selector_{scenario_name}.launch
Parameters
Name |
Type |
Description |
Default |
Range |
update_rate |
float |
timer's update rate |
10 |
≥0.0 |
th_max_message_delay_sec |
float |
threshold time of input messages' maximum delay |
1 |
≥0.0 |
th_arrived_distance_m |
float |
threshold distance to check if vehicle has arrived at the trajectory's endpoint |
1 |
≥0.0 |
th_stopped_time_sec |
float |
threshold time to check if vehicle is stopped |
1 |
≥0.0 |
th_stopped_velocity_mps |
float |
threshold velocity to check if vehicle is stopped |
0.01 |
≥0.0 |
enable_mode_switching |
boolean |
enable switching between scenario modes when ego is stuck in parking area |
1 |
N/A |
Flowchart