Skip to content

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 waypoints are grouped as shown in the following figure.

waypoint_grouping

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).

path_cut_self_intersection

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.

path_cut_mutual_intersection

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.

path_cut_start_edge_intersection

Goal connection#

The path is connected to the goal smoothly in the following way:

(a) The path has not reached the lane where the goal is placed, thus goal connection is not performed.

(b) The path has reached the goal lane and the end is inside the connection section. However, the longitudinal position of the path end is still in front of the goal, so it does not connect the path with the goal.

(c) The path has passed the goal (in terms of longitudinal position). In this case, the original path is cropped up to the connection section, and it is connected to the pre-goal and goal, sequentially. The pre-goal is inserted before the goal with the given offset, which helps align with the goal pose.

(d) If the start of the path is already inside the connection section, it just connects the path start, pre-goal, and goal.

goal_connection

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.

turn_signal_sections

If consecutive turns are required, the turn signal corresponding to the required section or the last section takes precedence.

turn_signal_conflict

Hazard signal#

This node always publishes a hazard signal of autoware_vehicle_msgs::msg::HazardLightsCommand::NO_COMMAND.

Flowchart#

uml diagram

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.connection_gradient_from_centerline float Gradient for connecting centerline and user-defined 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
goal_connection.connection_section_length float Length of goal connection section [m] 7.5 ≥0.0
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: