Path Generator#
The path_generator
node receives a route from mission_planner
and converts the center line into a path.
If the route has waypoints set, it generates a path passing through them.
This package is a simple alternative of behavior_path_generator
.
Path generation#
When input data is ready, it first searches for the lanelet closest to the vehicle.
If found, it gets the lanelets within a distance of path_length.backward
behind and path_length.forward
in front.
Their center lines are concatenated to generate a path.
If waypoints exist in the route, it replaces the overlapped segment of the center line with them. The overlap interval is determined as shown in the following figure.
Path cut#
If there is a self-intersection on either of the path bounds, the path is cut off a specified distance before the first intersection, as shown in the following figure (path: green, bound: blue).
Depending on the crossing angle, the return path's bound may be closer to the centerline than the outward's one, depicted in the diagram below. To deal with this, intersections of the left and right bounds (mutual intersection) are taken into account as well, and the path is cut at the nearest intersecting point.
Furthermore, in the case of the following figure, the return path goes inside even if mutual intersection is considered. Therefore, path cut is also made when the start edge of the path and the path bounds intersect.
Turn signal#
Turn signal is determined based on the rules defined for behavior_path_planner. (See here for details)
As a general rule, the turn signal is turned on at a specified distance before the lanelet in which a turn is designated, and turned off when the driving direction has changed to the specified degree.
If consecutive turns are required, the turn signal corresponding to the required section or the last section takes precedence.
Hazard signal#
This node always publishes a hazard signal of autoware_vehicle_msgs::msg::HazardLightsCommand::NO_COMMAND
.
Flowchart#
Input topics#
Name | Type | Description |
---|---|---|
~/input/odometry |
nav_msgs::msg::Odometry |
ego pose |
~/input/vector_map |
autoware_map_msgs::msg::LaneletMapBin |
vector map information |
~/input/route |
autoware_planning_msgs::msg::LaneletRoute |
current route from start to goal |
Output topics#
Name | Type | Description | QoS Durability |
---|---|---|---|
~/output/path |
autoware_internal_planning_msgs::msg::PathWithLaneId |
generated path | volatile |
~/output/turn_indicators_cmd |
autoware_vehicle_msgs::msg::TurnIndicatorsCommand |
turn signal | volatile |
~/output/hazard_lights_cmd |
autoware_vehicle_msgs::msg::HazardLightsCommand |
hazard signal | volatile |
Parameters#
Name | Type | Description | Default | Range |
---|---|---|---|---|
planning_hz | float | Planning frequency [Hz] | 10 | ≥0.0 |
path_length.backward | float | Length of generated path behind vehicle [m] | 5 | ≥0.0 |
path_length.forward | float | Length of generated path in front of vehicle [m] | 300 | ≥0.0 |
waypoint_group.separation_threshold | float | Maximum distance at which consecutive waypoints are considered to belong to the same group [m] | 1 | ≥0.0 |
waypoint_group.interval_margin_ratio | float | Ratio for determining length of switching section from centerline to waypoints | 10 | ≥0.0 |
turn_signal.search_time | float | Time to search for start point of desired section [s] | 3 | ≥0.0 |
turn_signal.search_distance | float | Distance to search for start point of desired section [m] | 30 | ≥0.0 |
turn_signal.resampling_interval | float | Resampling interval for section start point interpolation [m] | 1 | ≥0.0 |
turn_signal.angle_threshold_deg | float | Threshold for determining end point of required section [deg] | 15 | ≥0.0 |
smooth_goal_connection.search_radius_range | float | Search radius for smooth goal connection [m] | 7.5 | ≥0.0 |
smooth_goal_connection.pre_goal_offset | float | Offset for pre-goal [m] | 1 | ≥0.0 |
In addition, the following parameters should be provided to the node: