Package Summary
Tags | No category tags. |
Version | 0.43.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-04-04 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Fumiya Watanabe
- Satoshi Ota
- Zulfaqar Azmi
- Kosuke Takeuchi
- Tomoya Kimura
- Shumpei Wakabayashi
- Tomohito Ando
- Alqudah Mohammad
- Maxime Clement
Authors
Lane Change design
The Lane Change module is activated when lane change is needed (Ego is not on preferred lane), and activation requirements are satisfied.
Lane Change Requirements
Prerequisites
The type of lane boundary in the HD map has to be one of the following:
- Dashed lane marking: Lane changes are permitted in both directions.
- Dashed marking on the left and solid on the right: Lane changes are allowed from left to right.
- Dashed marking on the right and solid on the left: Lane changes are allowed from right to left.
-
allow_lane_change
tags is set astrue
Activation Conditions
The lane change module will activate under the following conditions :
- The ego-vehicle is NOT on a
preferred_lane
. - Distance to start of
target_lane
is less thanmaximum_prepare_length
- The ego-vehicle is NOT close to a regulatory element:
- Distance to next regulatory element is greater than
maximum_prepare_length
. - Considers distance to traffic light. (If param
regulation.traffic_light
is enabled) - Considers distance to crosswalk. (If param
regulation.crosswalk
is enabled) - Considers distance to intersection. (If param
regulation.intersection
is enabled)
- Distance to next regulatory element is greater than
!!! warning
If ego vehicle is stuck, lane change will be enabled near crosswalk/intersection. Ego is considered stuck if it stops more than `stuck_detection.stop_time`. Ego is considered to be stopping if its velocity is smaller than `stuck_detection.velocity`.
The following figure illustrates the logic for checking if lane change is required:
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
start
if (Is data available AND lanes available) then (no)
#LightPink:False;
stop
else (yes)
endif
:Get distance to target lane start;
if (Is dist to target lane start < max prepare dist) then (no)
#LightPink:False;
stop
else (yes)
endif
:Get distance to next regulatory element;
if (Is dist to next regulatory element < max prepare dist) then (yes)
#LightPink:False;
stop
else (no)
end if
#LightGreen:True;
stop
@enduml
Ready Conditions
- Valid lane change path is found.
- Lane change path is safe; does not collide with other dynamic objects.
- Lane change candidate path is approved by an operator.
Implementation
Lane change module uses a sampling based approach for generating a valid and safe lane changing trajectory. The process for generating the trajectory includes object filtering, metrics sampling, candidate paths generation, and lastly candidate paths evaluation. Additionally the lane change module is responsible for turn signal activation when appropriate, and inserting a stop point when necessary.
Global Flowchart
The following diagram, illustrates the overall flow of the lane change module implementation.
@startuml
start
#LightBlue:Update lane change data;
#LightBlue:Filter detected objects;
if (Is lane change required?) then (yes)
#LightBlue:Activate turn signal;
#LightBlue:Generate metrics samples;
if (Is valid metrics available) then (yes)
While (Can generate new candidate path?) is (TRUE)
if (Candidate path is valid & safe?) then (yes)
#LightBlue:Generate drivable area;
#LightBlue:Execute lane change path;
while (Can module transit to success state?) is (False)
if (Can module trasit to failure state?) then (yes)
if (Can cancel or abort?) then (yes)
#LightBlue:Cancel/Abort;
#Orange:Restart process;
stop
else (no)
endif
else (no)
endif
endwhile (True)
#LightGreen:SUCCESS;
stop
else (no)
endif
endwhile (FALSE)
else (no)
endif
else (no)
endif
#LightBlue:Insert stop point;
#LightBlue:Execute previous approved path;
#Orange:Restart process;
stop
@enduml
The lane change module first updates the necessary data for lane change such as lanes information and transient data. Then filters the detected objects to be used for safety evaluation (see Object Filtering).
If the lane change requirements are met, the turn signal is activated and the lane change module will proceed to generating a candidate path. Lane change candidate paths are generated by sampling different metrics and evaluating the validity of the corresponding generated trajectory. More details can be found in Generating Lane Change Candidate Path;
When a valid candidate path is generated, a safety evaluation is conducted to check for any risk of collision or hindrance. The details of the safety evaluation can be found in Safety Checks.
Once a valid and safe candidate path is found, the drivable area is generated and the path is executed. While executing the lane change maneuver, the safety of the approved path is continuously monitored to ensure there is no chance of collision or other hindrance. If the approved path remains safe and completion checks are met (see Lane Change Completion Checks) the module will transit to SUCCESS state. In case the approved path is deemed to be no longer safe, the lane change module will attempt to abort the lane change maneuver (see Aborting Lane Change). When the lane change maneuver is aborted successfully the module will transit to FAILURE state, and the process is restarted.
If the lane change module fails to find a valid and safe candidate path, the module will continue executing the previously approved path and insert a stop point along the path where appropriate, for more details refer to Stopping Behavior.
Generating Lane Change Candidate Path
The lane change candidate path is divided into two phases: preparation and lane-changing. The following figure illustrates each phase of the lane change candidate path.
The following chart illustrates the process of sampling candidate paths for lane change.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
start
if (Is current lanes, target lanes OR target neighbor lanes polygon empty?) then (yes)
#LightPink:Return prev approved path;
stop
else (no)
endif
:Get target objects;
:Calculate prepare phase metrics;
if(Is near terminal AND frenet enabled) then (yes)
group Frenet Candidate Paths #Lavender
:Calculate frenet candidates;
:Start loop through frenet candidates;
repeat
:Get candidate path;
if (Is valid candidate path?) then (yes)
if (Is candidate path safe?) then (yes)
#LightGreen:Return candidate path;
stop
else (no)
if (Is first valid path) then (yes)
:Store candidate path;
else (no)
endif
endif
else (no)
endif
repeat while (Finished looping frenet candidates) is (FALSE)
end group
else (no)
group Path Shifter Candidate Paths #LightCyan
:Start loop through prepare phase metrics;
repeat
:Get prepare segment;
if (Is LC start point outside target lanes range) then (yes)
if (Is found a valid path) then (yes)
#Orange:Return first valid path;
stop
else (no)
#LightPink:Return prev approved path;
stop
endif
else (no)
endif
:Calculate shift phase metrics;
:Start loop through shift phase metrics;
repeat
:Get candidate path;
note left: Details shown in the next chart
if (Is valid candidate path?) then (yes)
:Store candidate path;
if (Is candidate path safe?) then (yes)
#LightGreen:Return candidate path;
stop
else (no)
endif
else (no)
endif
repeat while (Finished looping shift phase metrics) is (FALSE)
repeat while (Is finished looping prepare phase metrics) is (FALSE)
endgroup
endif
if (Is found a valid path) then (yes)
#Orange:Return first valid path;
stop
else (no)
endif
#LightPink:Return prev approved path;
stop
@enduml
The following chart demonstrates the process of generating a valid candidate path with path shifter method.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
start
:Calculate resample interval;
:Get reference path from target lanes;
if (Is reference path empty?) then (yes)
#LightPink:Return;
stop
else (no)
endif
:Get LC shift line;
:Set lane change Info;
note left: set information from sampled prepare phase and shift phase metrics\n<color:red>(duration, length, velocity, and acceleration)
:Construct candidate path;
if (Candidate path has enough length?) then (yes)
#LightGreen:Return valid candidate path;
stop
else (no)
#LightPink:Return;
stop
endif
@enduml
Prepare Phase
The prepare phase is the first section of the lane change candidate path and the corresponding prepare segment consists of a subsection of the current reference path along the current lane. The length of the prepare phase trajectory is computed as follows.
prepare_distance = current_speed * prepare_duration + 0.5 * lon_acceleration * prepare_duration^2
The prepare phase trajectory is valid if:
- The length of the prepare phase trajectory is greater than the distance to start of target lane
- The length of the prepare phase trajectory is less than the distance to terminal start point
Lane-changing Phase
The lane-changing phase consists of the shifted path that moves ego from current lane to the target lane. Total duration of lane-changing phase is computed from the shift_length
, lateral_jerk
and lateral_acceleration
.
In principle, positive longitudinal acceleration is considered during lane-changing phase, and is computed as follows.
lane_changing_acceleration = std::clamp((max_path_velocity - initial_lane_changing_velocity) / lane_changing_time,
0.0, prepare_longitudinal_acc);
Where max_path_velocity
is the current path speed limit.
!!! warning
If the longitudinal acceleration of prepare phase is negative (slowing down), AND ego is near terminal, then the lane-changing longitudinal acceleration will also be negative and its value is decided by the parameter `lane_changing_decel_factor`.
The lane changing distance is then computed as follows.
lane_changing_distance = initial_lane_changing_velocity * lane_changing_duration + 0.5 * lon_acceleration * lane_changing_duration^2
The backward_length_buffer_for_end_of_lane
is added to allow some window for any possible delay, such as control or mechanical delay during brake lag.
Sampling Multiple Candidate Paths
In order to find a valid and safe lane change path it might be necessary to generate multiple candidate path samples. The lane change module does this by sampling one or more of: prepare_duration
, longitudinal_acceleration
, and lateral_acceleration
.
Prepare Duration Sampling
In principle, a fixed prepare duration is assumed when generating lane change candidate path. The default prepare duration value is determined from the min and max values set in the lane change parameters, as well as the duration of turn signal activation.
For example, when the lane change module first activates and turn signal is activated then prepare duration will be max_prepare_duration
, as time passes and a path is still not approved, the prepare duration will decrease gradually down to min_prepare_duration
. The formula is as follows.
prepare_duration = std::max(max_prepare_duration - turn_signal_duration, min_prepare_duration);
!!! note
When the current ego velocity is lower than the `min_lane_change_velocity`, the `min_prepare_duration` is adjusted to ensure sufficient time for reaching `min_lane_change_velocity` assuming `max_longitudinal_acceleration`.
!!! warning
The value of the prepare duration impacts lane change cancelling behavior. A shorter prepare duration results in a smaller window in which lane change maneuver can be cancelled. See [Evaluating Ego Vehicle's Position to Prevent Abrupt Maneuvers](#evaluating-ego-vehicles-position-to-prevent-abrupt-maneuvers) for more details.
When ego vehicles is close to the terminal start, we need to sample multiple prepare duration values to find a valid and safe path. In this case prepare duration values are sampled starting from max_prepare_duration
down to 0.0
at a fixed time interval of 0.5 s
.
Longitudinal Acceleration Sampling
In principle, maximum longitudinal acceleration is assumed for generating lane change candidate path. However in certain situations, we need to sample multiple longitudinal acceleration values to find a valid and safe candidate path. The lower and upper bounds of the longitudinal acceleration sampled are determined from the values specified in the lane change parameters and common planner parameters, as follows
maximum_longitudinal_acceleration = min(common_param.max_acc, lane_change_param.max_acc)
minimum_longitudinal_acceleration = max(common_param.min_acc, lane_change_param.min_acc)
where common_param
is vehicle common parameter, which defines vehicle common maximum longitudinal acceleration and deceleration. Whereas, lane_change_param
has maximum longitudinal acceleration and deceleration for the lane change module. For example, if a user set and common_param.max_acc=1.0
and lane_change_param.max_acc=0.0
, maximum_longitudinal_acceleration
becomes 0.0
, and the lane change does not accelerate in the lane change phase.
The longitudinal_acceleration_resolution
is determine by the following
longitudinal_acceleration_resolution = (maximum_longitudinal_acceleration - minimum_longitudinal_acceleration) / longitudinal_acceleration_sampling_num
The chart below illustrates the conditions under which longitudinal acceleration values are sampled.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
start
if (prev_module_path is empty?) then (yes)
:Return empty list;
stop
else (no)
endif
if (max_acc <= 0.0) then (yes)
:Return **sampled acceleration values**;
note left: Calculated sampled acceleration using\n<color:red>getAccelerationValues(min_acc, max_acc, longitudinal_acc_sampling_num)</color>
stop
endif
if (max_lane_change_length > ego's distance to the end of the current lanes.) then (yes)
:Return **sampled acceleration values**;
stop
endif
if (ego is stuck in the current lanes) then (yes)
:Return **sampled acceleration values**;
stop
else (no)
endif
if (is goal is in target lanes) then (yes)
if (max_lane_change_length < ego's distance to the goal along the target lanes) then (yes)
:Return {max_acc};
stop
else (no)
endif
else (no)
if (max_lane_change_length < ego's distance to the end of the target lanes.) then (yes)
:Return {max_acc};
stop
else (no)
endif
endif
:Return **sampled acceleration values**;
stop
@enduml
while the following describes the process by which longitudinal accelerations are sampled.
@startuml
start
:Initialize sampled_values with min_acc;
if (min_acc > max_acc) then (yes)
:Return empty list;
stop
elseif (max_acc - min_acc < epsilon) then (yes)
:Return {min_acc};
stop
else (no)
:Calculate resolution;
endif
:Start loop from min_acc to max_acc with resolution step;
repeat
if (sampled_values.back() < -epsilon AND next_value > epsilon) then (yes)
:Insert 0.0 into sampled_values;
else (no)
endif
:Add sampled_acc to sampled_values;
repeat while (sampled_acc < max_acc + epsilon) is (TRUE)
:Reverse sampled_values;
:Return sampled_values;
stop
@enduml
The following figure illustrates when longitudinal_acceleration_sampling_num = 4
. Assuming that maximum_acceleration = 1.0
and minimum_acceleration = 1.0
then a0 == 1.0
, a1 == 0.5
, a2 == 0.0
, a3 == -0.5
and a4 == -1.0
. a0
is the expected lane change trajectory when sampling is not required.
Which path will be chosen depends on validity and safety checks.
Lateral Acceleration Sampling
In addition to sampling longitudinal acceleration, we also sample lane change paths by varying the lateral acceleration. Lateral acceleration affects the lane changing duration, a lower value results in a longer trajectory, while a higher value results in a shorter trajectory. This allows the lane change module to explore shorter trajectories through higher lateral acceleration when there is limited space for the lane change.
The maximum and minimum lateral accelerations are defined in the lane change parameter file as a map. The range of lateral acceleration is determined for each velocity by linearly interpolating the values in the map. Let’s assume we have the following map
Ego Velocity | Minimum lateral acceleration | Maximum lateral acceleration |
---|---|---|
0.0 | 0.2 | 0.3 |
2.0 | 0.2 | 0.4 |
4.0 | 0.3 | 0.4 |
6.0 | 0.3 | 0.5 |
In this case, when the current velocity of the ego vehicle is 3.0, the minimum and maximum lateral accelerations are 0.25 and 0.4 respectively. These values are obtained by linearly interpolating the second and third rows of the map, which provide the minimum and maximum lateral acceleration values.
Within this range, we sample the lateral acceleration for the ego vehicle. Similar to the method used for sampling longitudinal acceleration, the resolution of lateral acceleration (lateral_acceleration_resolution) is determined by the following:
lateral_acceleration_resolution = (maximum_lateral_acceleration - minimum_lateral_acceleration) / lateral_acceleration_sampling_num
Terminal Lane Change Path
Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at terminal_start
and not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to terminal_start
is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively:
Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the terminal_start
position, as indicated by the dashed red line in the image above.
Generating Path Using Frenet Planner
!!! warning
Generating path using Frenet planner applies only when ego is near terminal start
If the ego vehicle is far from the terminal, the lane change module defaults to using the path shifter. This ensures that the lane change is completed while the target lane remains a neighbor of the current lane. However, this approach may result in high curvature paths near the terminal, potentially causing long vehicles to deviate from the lane.
To address this, the lane change module provides an option to choose between the path shifter and the Frenet planner. The Frenet planner allows for some flexibility in the lane change endpoint, extending the lane changing end point slightly beyond the current lane’s neighbors.
The following table provides comparisons between the planners
With Path Shifter | With Frenet Planner |
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
!!! note
The planner can be enabled or disabled using the `frenet.enable` flag.
!!! note
Since only a segment of the target lane is used as input to generate the lane change path, the end pose of the lane change segment may not smoothly connect to the target lane centerline. To address this, increase the value of `frenet.th_curvature_smoothing` to improve the smoothness.
!!! note
The yaw difference threshold (`frenet.th_yaw_diff`) limits the maximum curvature difference between the end of the prepare segment and the lane change segment. This threshold might prevent the generation of a lane change path when the lane curvature is high. In such cases, you can increase the frenet.th_yaw_diff value. However, note that if the prepare path was initially shifted by other modules, the resultant steering may not be continuous.
Candidate Path Validity
It is a prerequisite, that both prepare length and lane-changing length are valid, such that:
- The prepare segment length is greater than the distance from ego to target lane start.
- The prepare segment length is smaller than the distance from ego to terminal start.
- The lane-changing distance is smaller than the remaining distance after prepare segment to terminal end.
- The lane-changing distance is smaller than the remaining distance after prepare segment to the next regulatory element.
If so, a candidate path is considered valid if:
- The lane changing start point (end of prepare segment) is valid; it is within the target lane neighbor’s polygon.
- The distance from ego to the end of the current lanes is sufficient to perform a single lane change.
- The distance from ego to the goal along the current lanes is adequate to complete multiple lane changes.
- The distance from ego to the end of the target lanes is adequate for completing multiple lane changes.
The following flow chart illustrates the validity check.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #White
start
if (Check if start point is valid by check if it is covered by neighbour lanes polygon) then (not covered)
#LightPink:Reject path;
stop
else (covered)
endif
:Calculate total length and goal related distances;
if (total lane change length considering single lane change > distance from current pose to end of current lanes) then (yes)
#LightPink:Reject path;
stop
else (no)
endif
if (goal is in current lanes) then (yes)
if (total lane change length considering multiple lane changes > distance from ego to goal along current lanes) then (yes)
#LightPink:Reject path;
stop
else (no)
endif
else (no)
endif
if (target lanes is empty) then (yes)
#LightPink:Reject path;
stop
else (no)
endif
if (total lane change length considering multiple lane changes > distance from ego to the end of target lanes) then (yes)
#LightPink:Reject path;
stop
else (no)
endif
#LightGreen:Valid Candidate Path;
stop
@enduml
!!! warning
A valid path does NOT mean that the path is safe, however it will be available as a candidate path and can be force approved by operator. A path needs to be both valid AND safe to be automatically approved.
Lane Change Completion Checks
To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria.
For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the finish_judge_buffer
distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle’s current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets.
If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within finish_judge_lateral_threshold
distance from the target lane’s centerline, and the angle deviation must be within finish_judge_lateral_angle_deviation
degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle’s orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue.
The process of determining lane change completion is shown in the following diagram.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
title Lane change completion judge
start
:Calculate distance from current ego pose to lane change end pose;
if (Is ego velocity < 1.0?) then (<color:green><b>YES</b></color>)
:Set <b>finish_judge_buffer</b> to 0.0;
else (<color:red><b>NO</b></color>)
:Set <b>finish_judge_buffer</b> to lane_change_finish_judge_buffer;
endif
if (ego has passed the end_pose and ego is <b>finish_judge_buffer</b> meters away from end_pose?) then (<color:green><b>YES</b></color>)
if (Current ego pose is in target lanes' polygon?) then (<color:green><b>YES</b></color>)
:Lane change is <color:green><b>completed</b></color>;
stop
else (<color:red><b>NO</b></color>)
:Lane change is <color:red><b>NOT</b></color> completed;
stop
endif
else (<color:red><b>NO</b></color>)
endif
if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (<color:red><b>YES</b></color>)
:Lane change is <color:red><b>NOT</b></color> completed;
stop
else (<color:green><b>NO</b></color>)
:Calculate distance to the target lanes' centerline;
if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (<color:green><b>YES</b></color>)
:Lane change is <color:green><b>completed</b></color>;
stop
else (<color:red><b>NO</b></color>)
:Lane change is <color:red><b>NOT</b></color> completed;
stop
endif
endif
@enduml
Safety Checks
A candidate path needs to be both valid and safe for it to be executed. After generating a candidate path and validating it, the path will be checked against surrounding objects to ensure its safety. However the impacts of an object depends on its categorization, therefore it is necessary to filter the predicted objects before performing the safety checks.
Object filtering
In order to perform safety checks on the sampled candidate paths, it is needed to categorize the predicted objects based on their current pose and behavior at the time. These categories help determine how each object impacts the lane change process and guide the safety evaluation.
The predicted objects are divided into four main categories:
-
Target Lane Leading: Objects that overlap with the target lane and are in front of the ego vehicle. This category is further divided into three subcategories:
- Moving: Objects with a velocity above a certain threshold.
- Stopped: Stationary objects within the target lane.
- Stopped at Bound: Objects outside the target lane but close to its boundaries.
- Target Lane Trailing: Objects that overlap with the target lane or any lanes preceding the target lane. Only moving vehicles are included in this category.
- Current Lane: Objects in front of the ego vehicle in the ego vehicle’s current lane.
- Others: Any objects not classified into the above categories.
Furthermore, for Target Lane Leading and Current Lane objects, only those positioned within the lane boundary or before the goal position are considered. Objects exceeding the end of the lane or the goal position are classified as Others.
Once objects are filtered into their respective categories, they are sorted by distance closest to the ego vehicle to farthest.
The following diagram illustrates the filtering process,
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
title Filter Objects main flowchart
start
:Filter predicted objects by class;
note left: Remove objects whose classes are\nnot specified in the <color:red>**target_object**</color> parameter.
:Filter oncoming predicted objects;
note left: Compare ego's current pose and object's current pose,\nand filter out any object whose yaw difference exceeds\n<color:red>**collision_check.th_incoming_object_yaw**</color>;
:Transform predicted objects to extended predicted objects;
group "Filter target lane objects" {
if (Object's lateral distance\nfrom the centerline\nis more than\nhalf of ego's width?) then (TRUE)
if (Object's current pose\nis before the goal or\nthe end of the lane) then (TRUE)
if (Object overlaps target lane?) then (TRUE)
#LightGreen:To SUBPROCESS "Separate object based on its behavior in target lane";
if(can separate object in SUBPROCESS) then (TRUE)
stop
endif
else (FALSE)
if (Object is moving\nAND\nis a vehicle class\nAND\npath overlaps target lane?) then (TRUE)
#LightGreen:To SUBPROCESS "Separate object based on its behavior in target lane";
if(can separate object in SUBPROCESS) then (TRUE)
stop
endif
endif
endif
endif
#LightPink:From SUBPROCESS "Separate object based on its behavior in target lane";
if (Object is in expanded target lane\nAND\nis stopped\nAND\nin front of ego?) then (TRUE)
:Add object to <color:blue>**filtered_object.leading_objects.stopped_at_bound**</color> list;
stop
endif
else (FALSE)
if (Object overlaps preceding target lanes?) then (TRUE)
:Add object to <color:blue>**filtered_object.trailing_objects**</color> list;
stop
endif
endif
}
if (Object is in front of ego\nAND\nis before terminal\nAND\noverlaps current lane?) then (TRUE)
:Add object to <color:orange>**filtered_object.current_lane**</color> list;
stop
else (FALSE)
:Add object to <color:magenta>**filtered_object.others**</color> list;
endif
stop
group Target Lane Objects Subprocess #LightYellow
start
if (Object is behind ego?) then (TRUE)
if (Object is moving?) then (TRUE)
:Add object to <color:blue>**filtered_object.trailing_objects**</color> list;
#LightGreen:Can separate object;
stop
else (FALSE)
#LightPink:Cant separate proceed with other checks;
stop
endif
else (FALSE)
if (Object is moving?) then (TRUE)
:Add object to <color:blue>**filtered_object.leading_objects.moving**</color> list;
else (FALSE)
:Add object to <color:blue>**filtered_object.leading_objects.stopped**</color> list;
endif
#LightGreen:Can separate object;
stop
endif
@enduml
!!! note
As shown in the flowchart, oncoming objects are also filtered out. The filtering process considers the difference between the current orientation of the ego vehicle and that of the object. However, depending on the map's geometry, a certain threshold may need to be allowed. This threshold can be configured using the parameter collision_check.th_incoming_object_yaw.
!!! note
The **Target Lane Leading's Stopped at Boundary** objects are detected using the expanded area of the target lane beyond its original boundaries. The parameters `lane_expansion.left_offset` and `lane_expansion.right_offset` can be configured to adjust the expanded width.
<div align="center">
<table>
<tr>
<td>
<div style="text-align: center;">
<div style="color: black; font-size: 20px; margin-bottom: 10px;">Without Lane Expansion</div>
<img src="./images/lane_change-lane_expansion-without.png" alt="Without lane expansion">
</div>
</td>
<td>
<div style="text-align: center;">
<div style="color: black; font-size: 20px; margin-bottom: 10px;">With Lane Expansion</div>
<img src="./images/lane_change-lane_expansion-with.png" alt="With lane expansion">
</div>
</td>
</tr>
</table>
</div>
Candidate Path Safety
A candidate path is considered safe if:
- There are no overtaking objects when the ego vehicle exits the turn-direction lane. (see Overtaking Object Check)
- There is no parked vehicle along the target lane ahead of ego (see Delay Lane Change Check)
- The path does NOT cause ego footprint to exceed the target lane opposite boundary
- The path passes the collision check (See Collision Check)
Overtaking Object Check
When ego is exiting an intersection on a turning lane, there is a possibility that a rear vehicle will attempt to overtake the ego vehicle. Which can be dangerous if ego is also trying to perform a lane change. Therefore lane change module will adopt a more conservative behavior in such situation.
If the ego vehicle is currently within an intersection on a turning lane, as shown in the figure below, the generated candidate paths will be marked as unsafe.
Additionally, if the ego vehicle has just exited the turn lane of an intersection and its distance from the intersection is within the backward_length_from_intersection
, as shown in the figure below, the generated candidate paths will also be marked as unsafe.
Delay Lane Change Check
In certain situations, when there are stopped vehicles along the target lane ahead of Ego vehicle, to avoid getting stuck, it is desired to perform the lane change maneuver after the stopped vehicle. To do so, all static objects ahead of ego along the target lane are checked in order from closest to furthest, if any object satisfies the following conditions, lane change will be delayed and candidate path will be rejected.
- The distance from object to terminal end is sufficient to perform lane change
- The distance to object is less than the lane changing length
- The distance from object to next object is sufficient to perform lane change
If the parameter check_only_parked_vehicle
is set to true
, the check will only consider objects which are determined as parked.
More details on parked vehicle detection can be found in documentation for avoidance module.
The following flow chart illustrates the delay lane change check.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #White
start
if (Is target objects, candidate path, OR current lane path empty?) then (yes)
#LightPink:Return false;
stop
else (no)
endif
:Start checking objects from closest to furthest;
repeat
if (Is distance from object to terminal sufficient) then (yes)
else (no)
#LightPink:Return false;
stop
endif
if (Is distance to object less than lane changing length) then (yes)
else (no)
if (Is only check parked vehicles and vehicle is not parked) then (yes)
else (no)
if(Is last object OR distance to next object is sufficient) then (yes)
#LightGreen: Return true;
stop
else (no)
endif
endif
endif
repeat while (Is finished checking all objects) is (FALSE)
#LightPink: Return false;
stop
@enduml
The following figures demonstrate different situations under which delay action will or won’t be triggered. In each figure the target lane vehicles are assumed to be stopped. The target lane vehicle responsible for triggering the delay action is marked with blue color.
- Delay lane change will be triggered as there is sufficient distance ahead.
- Delay lane change will NOT be triggered as there is no sufficient distance ahead.
- Delay lane change will be triggered by fist NPC as there is sufficient distance ahead.
- Delay lane change will be triggered by second NPC as there is sufficient distance ahead.
- Delay lane change will NOT be triggered as there is no sufficient distance ahead.
Collision Check
To ensure the safety of the lane change candidate path an RSS check is performed against the surrounding predicted objects. More details on the collision check implementation can be found in safety check utils explanation
Collision Check In Prepare Phase
The collision check can be applied to the lane changing section only or to the entire candidate path by enabling the flag enable_collision_check_at_prepare_phase
. Enabling this flag ensures that the ego vehicle secures enough inter-vehicle distance ahead of target lane rear vehicle before attempting a lane change. The following image illustrates the differences between the false
and true
cases.
!!! note
When ego vehicles is stuck, i.e it is stopped, and there is an obstacle in front or is at end of current lane. Then the safety check for lane change is relaxed compared to normal times.
Stopping Behavior
The stopping behavior of the ego vehicle is determined based on various factors, such as the number of lane changes required, the presence of obstacles, and the position of blocking objects in relation to the lane change plan. The objective is to choose a suitable stopping point that allows for a safe and effective lane change while adapting to different traffic scenarios.
The following flowchart and subsections explain the conditions for deciding where to insert a stop point when an obstacle is ahead.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
title Inserting Stop Point
start
if (number of lane changes is zero?) then (<color:green><b>YES</b></color>)
stop
else (<color:red><b>NO</b></color>)
endif
if (do we want to insert stop point in current lanes?) then (<color:red><b>NO</b></color>)
#LightPink:Insert stop point at next lane change terminal start.;
stop
else (<color:green><b>YES</b></color>)
endif
if (Is there leading object in the current lanes that blocks ego's path?) then (<color:red><b>NO</b></color>)
#LightPink:Insert stop point at terminal stop.;
stop
else (<color:green><b>YES</b></color>)
endif
if (Blocking object's position is after target lane's start position?) then (<color:red><b>NO</b></color>)
#LightPink:Insert stop at the target lane's start position.;
stop
else (<color:green><b>YES</b></color>)
endif
if (Blocking object's position is before terminal stop position?) then (<color:red><b>NO</b></color>)
#LightPink:Insert stop at the terminal stop position;
stop
else (<color:green><b>YES</b></color>)
endif
if (Are there target lane objects between the ego and the blocking object?) then (<color:red><b>NO</b></color>)
#LightGreen:Insert stop behind the blocking object;
stop
else (<color:green><b>YES</b></color>)
#LightPink:Insert stop at terminal stop;
stop
@enduml
Ego vehicle’s stopping position when an object exists ahead
When the ego vehicle encounters an obstacle ahead, it stops while maintaining a safe distance to prepare for a possible lane change. The exact stopping position depends on factors like whether the target lane is clear or if the lane change needs to be delayed. The following explains how different stopping scenarios are handled:
When the near the end of the lane change
Whether the target lane has obstacles or is clear, the ego vehicle stops while keeping a safe distance from the obstacle ahead, ensuring there is enough room for the lane change.
When the ego vehicle is not near the end of the lane change
The ego vehicle stops while maintaining a safe distance from the obstacle ahead, ensuring there is enough space for a lane change.
Ego vehicle’s stopping position when an object exists in the lane changing section
If there are objects within the lane change section of the target lane, the ego vehicle stops closer to the obstacle ahead, without maintaining the usual distance for a lane change.
When near the end of the lane change
Regardless of whether there are obstacles in the target lane, the ego vehicle stops while keeping a safe distance from the obstacle ahead, allowing for the lane change.
When not near the end of the lane change
If there are no obstacles in the lane change section of the target lane, the ego vehicle stops while keeping a safe distance from the obstacle ahead to accommodate the lane change.
If there are obstacles within the lane change section of the target lane, the ego vehicle stops closer to the obstacle ahead, without keeping the usual distance needed for a lane change.
When the target lane is far away
If the target lane for the lane change is far away and not next to the current lane, the ego vehicle stops closer to the obstacle ahead, as maintaining the usual distance for a lane change is not necessary.
When target lane is blocked and multiple lane changes
When ego vehicle needs to perform multiple lane changes to reach the preferred_lane
, and the target_lane
is blocked, for example, due to incoming vehicles, the ego vehicle must stop at a sufficient distance from the lane end and wait for the target_lane
to clear. The minimum stopping distance can be computed from shift length and minimum lane changing velocity.
lane_changing_time = f(shift_length, lat_acceleration, lat_jerk)
minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_velocity * lane_changing_time + lane_change_finish_judge_buffer
The following figure illustrates when the lane is blocked in multiple lane changes cases.
Aborting Lane Change
Once the lane change path is approved, there are several situations where we may need to abort the maneuver. The abort process is triggered when any of the following conditions is met
- The ego vehicle is near a traffic light, crosswalk, or intersection, and it is possible to complete the lane change after the ego vehicle passes these areas.
- The target object list is updated, requiring us to delay lane change
- The lane change is forcefully canceled via RTC.
- The path has become unsafe. (see Checking Approved Path Safety)
Furthermore, if the path has become unsafe, there are three possible outcomes for the maneuver:
- CANCEL: The approved path has become unsafe while ego is still in prepare phase. Lane change path is canceled, and the ego vehicle resumes its previous maneuver.
- ABORT: The approved path has become unsafe while ego is in lane changing phase. Lane change module generates a return path to bring the ego vehicle back to its current lane.
- CRUISE or STOP: If aborting is not feasible, the ego vehicle continues with the lane change. Another module should decide whether the ego vehicle should cruise or stop in this scenario.
CANCEL can be enabled by setting the cancel.enable_on_prepare_phase
flag to true
, and ABORT can be enabled by setting the cancel.enable_on_lane_changing_phase
flag to true.
!!! warning
Enabling **CANCEL** is a prerequisite for enabling **ABORT**.
!!! warning
When **CANCEL** is disabled, all maneuvers will default to either **CRUISE** or **STOP**.
The chart shows the high level flow of the lane change abort process.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
title High-Level Flow of Lane Change Abort Process
while(Lane Following)
if (Lane Change required) then (**YES**)
if (Safe to change lane) then (<color:green><b>SAFE</b></color>)
:Approve safe path;
while(Lane change maneuver is completed?) is (**NO**)
if (Is cancel/abort Condition satisfied) then (**NO**)
else (**YES**)
if (Is Enough margin to retry lane change) then (**YES**)
if (Ego is preparing to change lane) then (**YES**)
#LightPink:CANCEL;
break
else (**NO**)
if (Overhang from current lanes is less than threshold?) then (**YES**)
#Cyan:ABORT;
break
else (NO)
endif
endif
else (**NO**)
endif
#Yellow:CRUISE/STOP;
endif
endwhile (**YES**)
else (<color:red><b>UNSAFE</b></color>)
endif
else (**NO**)
endif
endwhile
-[hidden]->
detach
@enduml
Preventing Oscillating Paths When Unsafe
Lane change paths can oscillate when conditions switch between safe and unsafe. To address this, a hysteresis count check is added before executing an abort maneuver. When the path is unsafe, the unsafe_hysteresis_count_
increases. If it exceeds the unsafe_hysteresis_threshold
, an abort condition check is triggered. This logic stabilizes the path approval process and prevents abrupt changes caused by temporary unsafe conditions.
@startuml
skinparam defaultTextAlignment center
skinparam backgroundColor #WHITE
title Hysteresis count flow for oscillation prevention
while (lane changing completed?) is (FALSE)
if (Perform collision check?) then (<color:green><b>SAFE</b></color>)
:Reset unsafe_hysteresis_count_;
else (<color:red><b>UNSAFE</b></color>)
:Increase unsafe_hysteresis_count_;
if (unsafe_hysteresis_count_ is more than\n unsafe_hysteresis_threshold?) then (<color:green><b>FALSE</b></color>)
else (<color:red><b>TRUE</b></color>)
#LightPink:Check abort condition;
-[hidden]->
detach
endif
endif
endwhile (TRUE)
stop
@enduml
Evaluating Ego Vehicle’s Position to Prevent Abrupt Maneuvers
To avoid abrupt maneuvers during CANCEL or ABORT, the lane change module ensures the ego vehicle can safely return to the original lane. This is done through geometric checks that verify whether the ego vehicle remains within the lane boundaries.
The edges of the ego vehicle’s footprint are compared against the boundary of the current lane to determine if they exceed the overhang tolerance, cancel.overhang_tolerance
. If the distance from any edge of the footprint to the boundary exceeds this threshold, the vehicle is considered to be diverging.
The footprints checked against the lane boundary include:
- Current Footprint: Based on the ego vehicle’s current position.
-
Future Footprint: Based on the ego vehicle’s estimated position after traveling a distance, calculated as $𝑑_{est}=𝑣_{ego} \cdot \Delta_{𝑡}$, where
- $v_{ego}$ is ego vehicle’s current velocity
- $\Delta_{t}$ is parameterized time constant value,
cancel.delta_time
.
as depicted in the following diagram
!!! note
The ego vehicle is considered capable of safely returning to the current lane only if **BOTH** the current and future footprint checks are `true`.
Checking Approved Path Safety
The lane change module samples accelerations along the path and recalculates velocity to perform safety checks. The motivation for this feature is explained in the Limitation section.
The computation of sampled accelerations is as follows:
Let
\[\text{resolution} = \frac{a_{\text{min}} - a_{\text{LC}}}{N}\]The sequence of sampled accelerations is then given as
\[\text{acc} = a_{\text{LC}} + k \cdot \text{resolution}, \quad k = [0, N]\]where
- $a_{\text{min}}$, is the minimum of the parameterized global acceleration constant
normal.min_acc
or the parameterized constanttrajectory.min_longitudinal_acceleration
. - $a_{\text{LC}}$ is the acceleration used to generate the approved path.
- $N$ is the parameterized constant
cancel.deceleration_sampling
If none of the sampled accelerations pass the safety check, the lane change path will be canceled, subject to the hysteresis check.
Cancel
Cancelling lane change is possible as long as the ego vehicle is in the prepare phase and has not started deviating from the current lane center line. When lane change is canceled, the approved path is reset. After the reset, the ego vehicle will return to following the original reference path (the last approved path before the lane change started), as illustrated in the following image:
The following parameters can be configured to tune the behavior of the cancel process:
- Safety constraints for cancel.
- Safety constraints for parked vehicle.
!!! note
To ensure feasible behavior, all safety constraint values must be equal to or less than their corresponding parameters in the [execution](#safety-constraints-during-lane-change-path-is-computed) settings.
- The closer the values, the more conservative the lane change behavior will be. This means it will be easier to cancel the lane change but harder for the ego vehicle to complete a lane change.
- The larger the difference, the more aggressive the lane change behavior will be. This makes it harder to cancel the lane change but easier for the ego vehicle to change lanes.
Abort
During the prepare phase, the ego vehicle follows the previously approved path. However, once the ego vehicle begins the lane change, its heading starts to diverge from this path. Resetting to the previously approved path in this situation would cause abrupt steering, as the controller would attempt to rapidly realign the vehicle with the reference trajectory.
Instead, the lane change module generates an abort path. This return path is specifically designed to guide the ego vehicle back to the current lane, avoiding any sudden maneuvers. The following image provides an illustration of the abort process.
The abort path is generated by shifting the approved lane change path using the path shifter. This ensures the continuity in lateral velocity, and prevents abrupt changes in the vehicle’s movement. The abort start shift and abort end shift are computed as follows:
- Start Shift: $d_{start}^{abort} = v_{ego} \cdot \Delta_{t}$
- End Shift: $d_{end}^{abort} = v_{ego} \cdot ( \Delta_{t} + t_{end} )$
- $v_{ego}$ is ego vehicle’s current velocity
- $\Delta_{t}$ is parameterized time constant value,
cancel.delta_time
. - $t_{end}$ is the parameterized time constant value,
cancel.duration
.
as depicted in the following diagram
!!! note
When executing the abort process, comfort is not a primary concern. However, due to safety considerations, limited real-world testing has been conducted to tune or validate this parameter. Currently, the maximum lateral jerk is set to an arbitrary value. To avoid generating a path with excessive lateral jerk, this value can be configured using `cancel.max_lateral_jerk`.
!!! note
Lane change module returns `ModuleStatus::FAILURE` once abort is completed.
Stop/Cruise
Once canceling or aborting the lane change is no longer an option, the ego vehicle will proceed with the lane change. This can happen in the following situations:
- The ego vehicle is performing a lane change near a terminal or dead-end, making it impossible to return to the original lane. In such cases, completing the lane change is necessary.
- If safety parameters are tuned too aggressively, it becomes harder to cancel or abort the lane change. This reduces tolerance for unexpected behaviors from surrounding vehicles, such as a trailing vehicle in the target lane suddenly accelerating or a leading vehicle suddenly decelerating. Aggressive settings leave less room for error during the maneuver.
Parameters
Essential lane change parameters
The following parameters are configurable in lane_change.param.yaml
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
time_limit |
[ms] | double | Time limit for lane change candidate path generation | 50.0 |
backward_lane_length |
[m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 |
backward_length_buffer_for_end_of_lane |
[m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 |
backward_length_buffer_for_blocking_object |
[m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 |
backward_length_from_intersection |
[m] | double | Distance threshold from the last intersection to invalidate or cancel the lane change path | 5.0 |
enable_stopped_vehicle_buffer |
[-] | bool | If true, will keep enough distance from current lane front stopped object to perform lane change when possible | true |
trajectory.max_prepare_duration |
[s] | double | The maximum preparation time for the ego vehicle to be ready to perform lane change. | 4.0 |
trajectory.min_prepare_duration |
[s] | double | The minimum preparation time for the ego vehicle to be ready to perform lane change. | 2.0 |
trajectory.lateral_jerk |
[m/s3] | double | Lateral jerk value for lane change path generation | 0.5 |
trajectory.minimum_lane_changing_velocity |
[m/s] | double | Minimum speed during lane changing process. | 2.78 |
trajectory.lon_acc_sampling_num |
[-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 |
trajectory.lat_acc_sampling_num |
[-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 |
trajectory.max_longitudinal_acc |
[m/s2] | double | maximum longitudinal acceleration for lane change | 1.0 |
trajectory.min_longitudinal_acc |
[m/s2] | double | maximum longitudinal deceleration for lane change | -1.0 |
trajectory.lane_changing_decel_factor |
[-] | double | longitudinal deceleration factor during lane changing phase | 0.5 |
trajectory.th_prepare_curvature |
[-] | double | If the maximum curvature of the prepare segment exceeds the threshold, the prepare segment is invalid. | 0.03 |
min_length_for_turn_signal_activation |
[m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 |
lateral_acceleration.velocity |
[m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] |
lateral_acceleration.min_values |
[m/s2] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] |
lateral_acceleration.max_values |
[m/s2] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.65, 0.65, 0.65] |
Parameter to judge if lane change is completed
The following parameters are used to judge lane change completion.
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
lane_change_finish_judge_buffer |
[m] | double | The longitudinal distance starting from the lane change end pose. | 2.0 |
finish_judge_lateral_threshold |
[m] | double | The lateral distance from targets lanes’ centerline. Used in addition with finish_judge_lateral_angle_deviation
|
0.1 |
finish_judge_lateral_angle_deviation |
[deg] | double | Ego angle deviation with reference to target lanes’ centerline. Used in addition with finish_judge_lateral_threshold
|
2.0 |
Lane change regulations
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
regulation.crosswalk |
[-] | boolean | Allow lane change in between crosswalks | true |
regulation.intersection |
[-] | boolean | Allow lane change in between intersections | true |
regulation.traffic_light |
[-] | boolean | Allow lane change to be performed in between traffic light | true |
Ego vehicle stuck detection
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
stuck_detection.velocity |
[m/s] | double | Velocity threshold for ego vehicle stuck detection | 0.1 |
stuck_detection.stop_time |
[s] | double | Stop time threshold for ego vehicle stuck detection | 3.0 |
Delay Lane Change
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
delay_lane_change.enable |
[-] | bool | Flag to enable/disable lane change delay feature | true |
delay_lane_change.check_only_parked_vehicle |
[-] | bool | Flag to limit delay feature for only parked vehicles | false |
delay_lane_change.min_road_shoulder_width |
[m] | double | Width considered as road shoulder if lane doesn’t have road shoulder when checking for parked vehicle | 0.5 |
delay_lane_change.th_parked_vehicle_shift_ratio |
[-] | double | Stopped vehicles beyond this distance ratio from center line will be considered as parked | 0.6 |
Terminal Lane Change Path
The following parameters are used to configure terminal lane change path feature.
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
terminal_path.enable |
[-] | bool | Flag to enable/disable terminal path feature | true |
terminal_path.disable_near_goal |
[-] | bool | Flag to disable terminal path feature if ego is near goal | true |
terminal_path.stop_at_boundary |
[-] | bool | If true, ego will stop at current lane boundary instead of middle of lane | false |
Generating Lane Changing Path using Frenet Planner
!!! warning
Only applicable when ego is near terminal start
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
frenet.enable |
[-] | bool | Flag to enable/disable frenet planner when ego is near terminal start. | true |
frenet.th_yaw_diff |
[deg] | double | If the yaw diff between of the prepare segment’s end and lane changing segment’s start exceed the threshold , the lane changing segment is invalid. | 10.0 |
frenet.th_curvature_smoothing |
[-] | double | Filters and appends target path points with curvature below the threshold to candidate path. | 0.1 |
Collision checks
Target Objects
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
target_object.car |
[-] | boolean | Include car objects for safety check | true |
target_object.truck |
[-] | boolean | Include truck objects for safety check | true |
target_object.bus |
[-] | boolean | Include bus objects for safety check | true |
target_object.trailer |
[-] | boolean | Include trailer objects for safety check | true |
target_object.unknown |
[-] | boolean | Include unknown objects for safety check | true |
target_object.bicycle |
[-] | boolean | Include bicycle objects for safety check | true |
target_object.motorcycle |
[-] | boolean | Include motorcycle objects for safety check | true |
target_object.pedestrian |
[-] | boolean | Include pedestrian objects for safety check | true |
common
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
safety_check.lane_expansion.left_offset |
[m] | double | Expand the left boundary of the detection area, allowing objects previously outside on the left to be detected and registered as targets. | 0.0 |
safety_check.lane_expansion.right_offset |
[m] | double | Expand the right boundary of the detection area, allowing objects previously outside on the right to be detected and registered as targets. | 0.0 |
Additional parameters
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
collision_check.enable_for_prepare_phase.general_lanes |
[-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If false , collision check only evaluated for lane changing phase. |
false |
collision_check.enable_for_prepare_phase.intersection |
[-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If false , collision check only evaluated for lane changing phase. |
true |
collision_check.enable_for_prepare_phase.turns |
[-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If false , collision check only evaluated for lane changing phase. |
true |
collision_check.check_current_lanes |
[-] | boolean | If true, the lane change module always checks objects in the current lanes for collision assessment. If false, it only checks objects in the current lanes when the ego vehicle is stuck. | false |
collision_check.check_other_lanes |
[-] | boolean | If true, the lane change module includes objects in other lanes when performing collision assessment. | false |
collision_check.use_all_predicted_paths |
[-] | boolean | If false, use only the predicted path that has the maximum confidence. | true |
collision_check.prediction_time_resolution |
[s] | double | Time resolution for object’s path interpolation and collision check. | 0.5 |
collision_check.yaw_diff_threshold |
[rad] | double | Maximum yaw difference between predicted ego pose and predicted object pose when executing rss-based collision checking | 3.1416 |
collision_check.th_incoming_object_yaw |
[rad] | double | Maximum yaw difference between current ego pose and current object pose. Objects with a yaw difference exceeding this value are excluded from the safety check. | 2.3562 |
safety constraints during lane change path is computed
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
safety_check.execution.expected_front_deceleration |
[m/s^2] | double | The front object’s maximum deceleration when the front vehicle perform sudden braking. (*1) | -1.0 |
safety_check.execution.expected_rear_deceleration |
[m/s^2] | double | The rear object’s maximum deceleration when the rear vehicle perform sudden braking. (*1) | -1.0 |
safety_check.execution.rear_vehicle_reaction_time |
[s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 |
safety_check.execution.rear_vehicle_safety_time_margin |
[s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 1.0 |
safety_check.execution.lateral_distance_max_threshold |
[m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 |
safety_check.execution.longitudinal_distance_min_threshold |
[m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
safety_check.execution.longitudinal_velocity_delta_time |
[m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |
safety_check.execution.extended_polygon_policy |
[-] | string | Policy used to determine the polygon shape for the safety check. Available options are: rectangle or along-path . |
rectangle |
safety constraints specifically for stopped or parked vehicles
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
safety_check.parked.expected_front_deceleration |
[m/s^2] | double | The front object’s maximum deceleration when the front vehicle perform sudden braking. (*1) | -1.0 |
safety_check.parked.expected_rear_deceleration |
[m/s^2] | double | The rear object’s maximum deceleration when the rear vehicle perform sudden braking. (*1) | -2.0 |
safety_check.parked.rear_vehicle_reaction_time |
[s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.0 |
safety_check.parked.rear_vehicle_safety_time_margin |
[s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 |
safety_check.parked.lateral_distance_max_threshold |
[m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 |
safety_check.parked.longitudinal_distance_min_threshold |
[m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
safety_check.parked.longitudinal_velocity_delta_time |
[m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |
safety_check.parked.extended_polygon_policy |
[-] | string | Policy used to determine the polygon shape for the safety check. Available options are: rectangle or along-path . |
rectangle |
safety constraints to cancel lane change path
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
safety_check.cancel.expected_front_deceleration |
[m/s^2] | double | The front object’s maximum deceleration when the front vehicle perform sudden braking. (*1) | -1.0 |
safety_check.cancel.expected_rear_deceleration |
[m/s^2] | double | The rear object’s maximum deceleration when the rear vehicle perform sudden braking. (*1) | -2.0 |
safety_check.cancel.rear_vehicle_reaction_time |
[s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.5 |
safety_check.cancel.rear_vehicle_safety_time_margin |
[s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 |
safety_check.cancel.lateral_distance_max_threshold |
[m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 |
safety_check.cancel.longitudinal_distance_min_threshold |
[m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 2.5 |
safety_check.cancel.longitudinal_velocity_delta_time |
[m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.6 |
safety_check.cancel.extended_polygon_policy |
[-] | string | Policy used to determine the polygon shape for the safety check. Available options are: rectangle or along-path . |
rectangle |
safety constraints used during lane change path is computed when ego is stuck
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
safety_check.stuck.expected_front_deceleration |
[m/s^2] | double | The front object’s maximum deceleration when the front vehicle perform sudden braking. (*1) | -1.0 |
safety_check.stuck.expected_rear_deceleration |
[m/s^2] | double | The rear object’s maximum deceleration when the rear vehicle perform sudden braking. (*1) | -1.0 |
safety_check.stuck.rear_vehicle_reaction_time |
[s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 |
safety_check.stuck.rear_vehicle_safety_time_margin |
[s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 1.0 |
safety_check.stuck.lateral_distance_max_threshold |
[m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 |
safety_check.stuck.longitudinal_distance_min_threshold |
[m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
safety_check.stuck.longitudinal_velocity_delta_time |
[m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |
safety_check.stuck.extended_polygon_policy |
[-] | string | Policy used to determine the polygon shape for the safety check. Available options are: rectangle or along-path . |
rectangle |
(*1) the value must be negative.
Abort lane change
The following parameters are configurable in lane_change.param.yaml
.
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
cancel.enable_on_prepare_phase |
[-] | boolean | Enable cancel lane change | true |
cancel.enable_on_lane_changing_phase |
[-] | boolean | Enable abort lane change. | false |
cancel.delta_time |
[s] | double | The time taken to start steering to return to the center line. | 3.0 |
cancel.duration |
[s] | double | The time taken to complete returning to the center line. | 3.0 |
cancel.max_lateral_jerk |
[m/sss] | double | The maximum lateral jerk for abort path | 1000.0 |
cancel.overhang_tolerance |
[m] | double | Lane change cancel is prohibited if the vehicle head exceeds the lane boundary more than this tolerance distance | 0.0 |
cancel.unsafe_hysteresis_threshold |
[-] | int | threshold that helps prevent frequent switching between safe and unsafe decisions | 10 |
cancel.deceleration_sampling_num |
[-] | int | Number of deceleration patterns to check safety to cancel lane change | 5 |
Debug
The following parameters are configurable in lane_change.param.yaml
.
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
publish_debug_marker |
[-] | boolean | Flag to publish debug marker | false |
Debug Marker & Visualization
To enable the debug marker, execute (no restart is needed)
ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner lane_change.publish_debug_marker true
or simply set the publish_debug_marker
to true
in the lane_change.param.yaml
for permanent effect (restart is needed).
Then add the marker
/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_left
in rviz2
.
Available information
- Ego to object relation, plus safety check information
- Ego vehicle interpolated pose up to the latest safety check position.
- Object is safe or not, shown by the color of the polygon (Green = Safe, Red = unsafe)
- Valid candidate paths.
- Position when lane changing start and end.
Limitation
- When a lane change is canceled, the lane change module returns
ModuleStatus::FAILURE
. As the module is removed from the approved module stack (see Failure modules), a new instance of the lane change module is initiated. Due to this, any information stored prior to the reset is lost. For example, thelane_change_prepare_duration
in theTransientData
is reset to its maximum value. - The lane change module has no knowledge of any velocity modifications introduced to the path after it is approved. This is because other modules may add deceleration points after subscribing to the behavior path planner output, and the final velocity is managed by the velocity smoother. Since this limitation affects CANCEL, the lane change module mitigates it by sampling accelerations along the approved lane change path. These sampled accelerations are used during safety checks to estimate the velocity that might occur if the ego vehicle decelerates.
- Ideally, the abort path should account for whether its execution would affect trailing vehicles in the current lane. However, the lane change module does not evaluate such interactions or assess whether the abort path is safe. As a result, the abort path is not guaranteed to be safe. To minimize the risk of unsafe situations, the abort maneuver is only permitted if the ego vehicle has not yet diverged from the current lane.
- Due to limited resources, the abort path logic is not fully optimized. The generated path may overshoot, causing the return trajectory to slightly shift toward the opposite lane. This can be dangerous, especially if the opposite lane has traffic moving in the opposite direction. Furthermore, the logic does not account for different vehicle types, which can lead to varying effects. For instance, the behavior might differ significantly between a bus and a small passenger car.
Changelog for package autoware_behavior_path_lane_change_module
0.43.0 (2025-03-21)
- Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
- chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
- fix(lane_change_module): fix planning factor issue
(#10244)
- when computing target lanes, don't include preceding lanes of lane change lane
- dont insert stop point on target lane if next lc dist buffer is zero
- return previous module output if LC module status is IDLE
* disable faulty test ---------
- Contributors: Hayato Mizushima, Yutaka Kondo, mkquda
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
- chore(lane_change, QC): remove unused function (#10188) chore(lane_change): remove unused function
- fix(lane_change): remove string literals from stopwatch toc (#10121)
- feat(lane_change): improve the calculation of the target lateral velocity in Frenet frame (#10078)
- fix(lane_change): fix end pose not connected to goal (RT1-9247) (#10103)
- feat!: replace tier4_planning_msgs/PathWithLaneId with autoware_internal_planning_msgs/PathWithLaneId (#10023)
- feat(planning_test_manager): abstract message-specific functions
(#9882)
- abstract message-specific functions
- include necessary header
- adapt velocity_smoother to new test manager
- adapt behavior_velocity_planner to new test manager
- adapt path_optimizer to new test manager
- fix output subscription
- adapt behavior_path_planner to new test manager
- adapt scenario_selector to new test manager
- adapt freespace_planner to new test manager
- adapt planning_validator to new test manager
- adapt obstacle_stop_planner to new test manager
- adapt obstacle_cruise_planner to new test manager
- disable test for freespace_planner
- adapt behavior_velocity_crosswalk_module to new test manager
- adapt behavior_path_lane_change_module to new test manager
- adapt behavior_path_avoidance_by_lane_change_module to new test manager
- adapt behavior_path_dynamic_obstacle_avoidance_module to new test manager
- adapt behavior_path_external_request_lane_change_module to new test manager
- adapt behavior_path_side_shift_module to new test manager
- adapt behavior_path_static_obstacle_avoidance_module to new test manager
- adapt path_smoother to new test manager
- adapt behavior_velocity_blind_spot_module to new test manager
- adapt behavior_velocity_detection_area_module to new test manager
- adapt behavior_velocity_intersection_module to new test manager
- adapt behavior_velocity_no_stopping_area_module to new test manager
- adapt behavior_velocity_run_out_module to new test manager
- adapt behavior_velocity_stop_line_module to new test manager
- adapt behavior_velocity_traffic_light_module to new test manager
- adapt behavior_velocity_virtual_traffic_light_module to new test manager
- adapt behavior_velocity_walkway_module to new test manager
- adapt motion_velocity_planner_node_universe to new test manager
- include necessary headers
* Odometries -> Odometry ---------Co-authored-by: Takayuki Murooka <<takayuki5168@gmail.com>>
- Contributors: Fumiya Watanabe, Mamoru Sobue, Maxime CLEMENT, Mert Çolak, Mitsuhiro Sakamoto, Ryohsuke Mitsudome, Zulfaqar Azmi, 心刚
0.41.2 (2025-02-19)
- chore: bump version to 0.41.1 (#10088)
- Contributors: Ryohsuke Mitsudome
0.41.1 (2025-02-10)
0.41.0 (2025-01-29)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- docs(lane_change): update lane change documentation
(#9949)
- update lane change requirements documentation
- remove unused function getNumToPreferredLane
- update candidate path generation documentation
- update prepare phase and lane changing phase documentation
- update longitudinal acceleration sampling documentation
- add prepare duration sampling documentation
- update candidate path validity and safety documentation
- fix formatting
- update image and fix formatting
- add overtaking turn lane documentation
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- add LC global flowchart to documentation
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- reorganize lane change documentation
- fix section title
- add global flowchart description
- add warning
- apply pre-commit checks
- fix spelling
* edit some descriptions ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- docs(lane_change): object filtering description
(#9947)
- docs(lane_change): object filtering description
- Move section up
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- refactor(behavior_path_planner): common test functions
(#9963)
- feat: common test code in behavior_path_planner
- deal with other modules
- fix typo
* update
- refactor(lane_change): add missing safety check parameter
(#9928)
- refactor(lane_change): parameterize incoming object yaw threshold
- Readme
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- Add missing parameters
- missing dot
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> * update readme ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (#9927) Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>> Co-authored-by: Ryohsuke Mitsudome <<43976834+mitsudome-r@users.noreply.github.com>> Co-authored-by: satoshi-ota <<satoshi.ota928@gmail.com>>
- feat(lane_change): ensure path generation doesn't exceed time
limit
(#9908)
- add time limit for lane change candidate path generation
- apply time limit for frenet method as well
- ensure param update value is valid
- fix param update initial value
- fix spelling
* fix param update initial values ---------
- feat(lane_change_module): add update paramter function for non
defined paramters
(#9887)
- feat(lane_change_module): add new parameters for collision check and delay lane change functionality
- feat(lane_change_module): add validation for longitudinal and lateral acceleration sampling parameters
* feat(lane_change): update parameter handling and add lateral acceleration mapping ---------
- feat(lane_change): using frenet planner to generate lane change
path when ego near terminal
(#9767)
- frenet planner
- minor refactoring
- adding parameter
- Add diff th param
- limit curvature for prepare segment
- minor refactoring
- print average curvature
- refactor
- filter the path directly
- fix some conflicts
- include curvature smoothing
- document
- fix image folder
- image size
- doxygen
- add debug for state
- use sign function instead
- rename argument
- readme
- fix failed test due to empty value
- add additional note
* fix conflict ---------
- feat(lane_change): append candidate path index to metric debug table (#9885) add candidate path index to metrics debug table
- docs(lane_change): fix broken link (#9892)
- docs(lane_change): explaining cancel and abort process
(#9845)
- docs(lane_change): explaining cancel and abort process
- slight fix in formatting
- rephrase sentence
- rephrase and replace image for cancel
- Cancel explanations and limitations
- revise abort figure
- revise flow chart
- rephase sentence
- minor fix
- finish up
- offers change to reduces for negative connotation
- minor fix
- move limitation all the way down
- precommit
- equation mistake
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> * rename subheading ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- refactor(lane_change): refactor transit failure function
(#9835)
- refactor(lane_change): refactor transit failure function
- fixed failed scenario
- remove is abort from debug
- set is abort state
- add comments for clarity
* include what you use. ---------
- feat(lane_change): implement terminal lane change feature
(#9592)
- implement function to compute terminal lane change path
- push terminal path to candidate paths if no other valid candidate path is found
- use terminal path in LC interface planWaitingApproval function
- set lane changing longitudinal accel to zero for terminal lc path
- rename function
- chore: rename codeowners file
- remove unused member variable prev_approved_path_
- refactor stop point insertion for terminal lc path
- add flag to enable/disable terminal path feature
- update README
- add parameter to configure stop point placement
- compute terminal path only when near terminal start
- add option to disable feature near goal
- set default flag value to false
- add documentation for terminal lane change path
- ensure actual prepare duration is always above minimum prepare duration threshold
- explicitly return std::nullopt
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- fix assignment
- fix spelling
* fix merge errors ---------Co-authored-by: tomoya.kimura <<tomoya.kimura@tier4.jp>> Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- feat(lane_change): add text display for candidate path sampling
metrics
(#9810)
- display candidate path sampling metrics on rviz
* rename struct ---------
- feat(lane_change): revise current lane objects filtering
(#9785)
- consider stopped front objects
- simplify computation of dist to front current lane object
- add flag to enable/disable keeping distance from front stopped vehicle
* fix object filtering test ---------
- refactor(lane_change): replace sstream to fmt for marker's text (#9775)
- feat(lane_change): add info text to virtual wall
(#9783)
- specify reason for lane change stop line
* add stop reason for incoming rear object ---------
- fix(lane_change): add metrics to valid paths visualization
(#9737)
- fix(lane_change): add metrics to valid paths visualization
* fix cpp-check error ---------
- refactor(lane_change): separate path-related function to utils/path
(#9633)
- refactor(lane_change): separate path-related function to utils/path
- remove old terminal lane change computation
- doxygen comments
- remove frenet planner header
- minor refactoring by throwing instead
- minor refactoring
- fix docstring and remove redundant argument
- get logger in header
- add docstring
- rename function is_colliding
- Fix failing test
- fix for failing scenario caused by prepare velocity
* fix error message ---------
- fix(lane_change): fix prepare length too short at low speed (RT1-8909) (#9735) fix prepare length too short at low speed (RT1-8909)
- refactor(lane_change): separate structs to different folders (#9625)
- fix(lane_change): remove overlapping preceding lanes
(#9526)
- fix(lane_change): remove overlapping preceding lanes
- fix cpp check
- start searching disconnected lanes directly
- just remove starting from overlapped found
- return non reversed lanes
* fix precommit ---------
- Contributors: Fumiya Watanabe, Kyoichi Sugahara, Mamoru Sobue, Takayuki Murooka, Zulfaqar Azmi, mkquda
0.40.0 (2024-12-12)
- Merge branch 'main' into release-0.40.0
- Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
- feat(behavior_path_planner): add detail text to virutal wall
(#9600)
- feat(behavior_path_planner): add detail text to virutal wall
- goal is far
- pull over start pose is far
- fix lc build
- fix build
* Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp ---------
- fix: fix ticket links in CHANGELOG.rst (#9588)
- fix(lane_change): check obj predicted path when filtering
(#9385)
- RT1-8537 check object's predicted path when filtering
- use ranges view in get_line_string_paths
- check only vehicle type predicted path
- Refactor naming
- fix grammatical
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> * precommit and grammar fix ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- chore(package.xml): bump version to 0.39.0
(#9587)
- chore(package.xml): bump version to 0.39.0
- fix: fix ticket links in CHANGELOG.rst
* fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>
- fix: fix ticket links in CHANGELOG.rst (#9588)
- feat(lane_change): reduce prepare duration when blinker has been
activated
(#9185)
- add minimum prepare duration parameter
- reduce prepare duration according to signal activation time
* chore: update CODEOWNERS (#9203) Co-authored-by: github-actions <<github-actions@github.com>>
- refactor(time_utils): prefix package and namespace with autoware (#9173)
- refactor(time_utils): prefix package and namespace with autoware
- refactor(time_utils): prefix package and namespace with autoware
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(rtc_interface): add requested field (#9202)
- add requested feature
* Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>> ---------Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>>
- fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (#9199)
* fix(bpp): prevent accessing nullopt (#9204) fix(bpp): calcDistanceToRedTrafficLight null
- refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (#9201)
- refactor: grouping functions
- refactor: grouping parameters
- refactor: rename member road_users_history to road_users_history_
- refactor: separate util functions
- refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node
- refactor: Add explicit template instantiation for removeOldObjectsHistory function
- refactor: Add tf2_geometry_msgs to data_structure
- refactor: Remove unused variables and functions in map_based_prediction_node.cpp
- Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp
- Apply suggestions from code review
* style(pre-commit): autofix ---------Co-authored-by: Mamoru Sobue <<hilo.soblin@gmail.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (#8912)
- Moved ndt_omp into ndt_scan_matcher
- Added Copyright
- style(pre-commit): autofix
- Fixed include
- Fixed cast style
- Fixed include
- Fixed honorific title
- Fixed honorific title
- style(pre-commit): autofix
- Fixed include hierarchy
- style(pre-commit): autofix
- Fixed include hierarchy
- style(pre-commit): autofix
- Fixed hierarchy
- Fixed NVTP to NVTL
- Added cspell:ignore
- Fixed miss spell
- style(pre-commit): autofix
- Fixed include
- Renamed applyFilter
- Moved ***_impl.hpp from include/ to src/
- style(pre-commit): autofix
- Fixed variable scope
* Fixed to pass by reference ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(autoware_test_utils): add traffic light msgs parser (#9177)
- modify implementation to compute and keep actual prepare duration in transient data
- if LC path is approved, set prepare duration in transient data from approved path prepare duration
- change default value of LC param min_prepare_duration
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- add function to set signal activation time, add docstring for function calc_actual_prepare_duration
- check for zero value max_acc to avoid division by zero
- chore: rename codeowners file
- chore: rename codeowners file
- chore: rename codeowners file
- allow decelerating in lane changing phase near terminal
- fix spelling
- fix units
- allow decelerating in lane changing phase near terminal
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- run pre-commit check
- fix spelling
- fix format
- allow decelerating in lane changing phase near terminal
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- run pre-commit check
- fix spelling
* fix format ---------Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]\@users.noreply.github.com> Co-authored-by: github-actions <<github-actions@github.com>> Co-authored-by: Esteve Fernandez <<33620+esteve@users.noreply.github.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Go Sakayori <<go-sakayori@users.noreply.github.com>> Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>> Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>> Co-authored-by: Taekjin LEE <<taekjin.lee@tier4.jp>> Co-authored-by: Mamoru Sobue <<hilo.soblin@gmail.com>> Co-authored-by: SakodaShintaro <<shintaro.sakoda@tier4.jp>> Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> Co-authored-by: tomoya.kimura <<tomoya.kimura@tier4.jp>>
- feat(lane_changing): improve computation of lane changing
acceleration
(#9545)
- allow decelerating in lane changing phase near terminal
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- run pre-commit check
- fix spelling
* fix format ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- fix(cpplint): include what you use - planning (#9570)
- refactor(test_utils): return parser as optional (#9391) Co-authored-by: Mamoru Sobue <<hilo.soblin@gmail.com>>
- fix(lane_change): cap ego's predicted path velocity (RT1-8505)
(#9341)
- fix(lane_change): cap ego's predicted path velocity (RT1-8505)
- properly cap based on 0.0 instead of min lc vel
* fix build error ---------
- fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-unused-variable (#9401)
- feat(lane_change): improve delay lane change logic
(#9480)
- implement function to check if lane change delay is required
- refactor function isParkedObject
- refactor delay lane change parameters
- update lc param yaml
- separate target lane leading objects based on behavior (RT1-8532)
- fixed overlapped filtering and lanes debug marker
- combine filteredObjects function
- renaming functions and type
- update some logic to check is stopped
- rename expanded to stopped_outside_boundary
- Include docstring
- rename stopped_outside_boundary → stopped_at_bound
* Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- spell-check
- add docstring for function is_delay_lane_change
- remove unused functions
- fix spelling
- add delay parameters to README
- add documentation for delay lane change behavior
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- run pre-commit checks
* only check for delay lc if feature is enabled ---------Co-authored-by: Zulfaqar Azmi <<zulfaqar.azmi@tier4.jp>> Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-error (#9402)
- fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-overloaded-virtual (#9400)
- feat(lane_change): parse predicted objects for lane change test
(RT1-8251)
(#9256)
- RT1-8251 parse predicted objects
- fix pre-commit and build error
- add additional test and fix test failure
- fix lint_cmake failure
- use expect instead
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- refactor(lane_change): refactor lane change parameters
(#9403)
- refactor lane change parameters
- update lane change param yaml
- update lane change README
- regroup some parameters
- run pre-commit prettier step
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * apply pre-commit checks ---------Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- 0.39.0
- update changelog
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- refactor(lane_change): separate target lane leading based on obj
behavior
(#9372)
- separate target lane leading objects based on behavior (RT1-8532)
- fixed overlapped filtering and lanes debug marker
- combine filteredObjects function
- renaming functions and type
- update some logic to check is stopped
- rename expanded to stopped_outside_boundary
- Include docstring
- rename stopped_outside_boundary → stopped_at_bound
* Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> * spell-check ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- feat(lane_change): output velocity factor (#9349)
- refactor(lane_change): refactor extended object safety check
(#9322)
- refactor LC extended object collision check code
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> ---------Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- refactor(bpp): rework steering factor interface
(#9325)
- refactor(bpp): rework steering factor interface
- refactor(soa): rework steering factor interface
- refactor(AbLC): rework steering factor interface
- refactor(doa): rework steering factor interface
- refactor(lc): rework steering factor interface
- refactor(gp): rework steering factor interface
- refactor(sp): rework steering factor interface
- refactor(sbp): rework steering factor interface
* refactor(ss): rework steering factor interface ---------
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- refactor(lane_change): remove std::optional from lanes polygon (#9288)
- fix(lane_change): extending lane change path for multiple lane
change (RT1-8427)
(#9268)
- RT1-8427 extending lc path for multiple lc
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- fix(lane_change): correct computation of maximum lane changing length threshold (#9279) fix computation of maximum lane changing length threshold
- refactor(lane_change): revert "remove std::optional from lanes polygon" (#9272) Revert "refactor(lane_change): remove std::optional from lanes polygon (#9267)" This reverts commit 0c70ea8793985c6aae90f851eeffdd2561fe04b3.
- refactor(lane_change): remove std::optional from lanes polygon (#9267)
- fix(lane_change): enable cancel when ego in turn direction lane
(#9124)
- RT0-33893 add checks from prev intersection
- fix shadow variable
- fix logic
- update readme
* refactor get_ego_footprint ---------
- test(bpp_common): add unit test for safety check
(#9223)
- add test for object collision
- add test for more functions
- add docstring
* fix lane change ---------
- Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo, Zulfaqar Azmi, kobayu858, mkquda
0.39.0 (2024-11-25)
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- refactor(lane_change): remove std::optional from lanes polygon (#9288)
- fix(lane_change): extending lane change path for multiple lane
change (RT1-8427)
(#9268)
- RT1-8427 extending lc path for multiple lc
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- fix(lane_change): correct computation of maximum lane changing length threshold (#9279) fix computation of maximum lane changing length threshold
- refactor(lane_change): revert "remove std::optional from lanes polygon" (#9272) Revert "refactor(lane_change): remove std::optional from lanes polygon (#9267)" This reverts commit 0c70ea8793985c6aae90f851eeffdd2561fe04b3.
- refactor(lane_change): remove std::optional from lanes polygon (#9267)
- fix(lane_change): enable cancel when ego in turn direction lane
(#9124)
- RT0-33893 add checks from prev intersection
- fix shadow variable
- fix logic
- update readme
* refactor get_ego_footprint ---------
- test(bpp_common): add unit test for safety check
(#9223)
- add test for object collision
- add test for more functions
- add docstring
* fix lane change ---------
- Contributors: Esteve Fernandez, Go Sakayori, Yutaka Kondo, Zulfaqar Azmi, mkquda
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- fix(behavior_path_planner, behavior_velocity_planner): fix to
not read invalid ID
(#9103)
- fix(behavior_path_planner, behavior_velocity_planner): fix to not read invalid ID
- style(pre-commit): autofix
- fix typo
* fix(behavior_path_planner, behavior_velocity_planner): fix typo and indentation ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- refactor(lane_change): refactor longitudinal acceleration sampling
(#9091)
- fix calc_all_max_lc_lengths function
- remove unused functions
- remove limit on velocity in calc_all_max_lc_lengths function
- sample longitudinal acceleration separately for each prepater duration
- refactor prepare phase metrics calculation
- check for zero value prepare duration
* refactor calc_lon_acceleration_samples function ---------
- feat(autoware_test_utils): add path with lane id parser
(#9098)
- add path with lane id parser
* refactor parse to use template ---------
- feat(lane_change): add unit test for normal lane change class
(RT1-7970)
(#9090)
- RT1-7970 testing base class
- additional test
- Added update lanes
- check path generation
- check is lane change required
* fix PRs comment ---------
- refactor(lane_change): reducing clang-tidy warnings
(#9085)
- refactor(lane_change): reducing clang-tidy warnings
* change function name to snake case ---------
- refactor(object_recognition_utils): add autoware prefix to object_recognition_utils (#8946)
- refactor(bpp_common, motion_utils): move path shifter util
functions to autoware::motion_utils
(#9081)
- remove unused function
- mover path shifter utils function to autoware motion utils
- minor change in license header
- fix warning message
* remove header file ---------
- fix(lane_change): insert stop for current lanes object (RT0-33761)
(#9070)
- RT0-33761 fix lc insert stop for current lanes object
- fix wrong value used for comparison
- ignore current lane object that is not on ego's path
- remove print
- update readme
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- revert is_within_vel_th removal
- fix flowchart too wide
- rename variable in has_blocking_target_object_for_stopping
- Add docstring and rename function
* change color ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- refactor(lane_change): refactor get_lane_change_lanes function
(#9044)
- refactor(lane_change): refactor get_lane_change_lanes function
* Add doxygen comment for to_geom_msg_pose ---------
- refactor(lane_change): replace any code that can use transient data
(#8999)
- RT1-8004 replace hasEnoughLength
- RT1-8004 Removed isNearEndOfCurrentLanes
- RT1-8004 refactor sample longitudinal acc values
- remove calc maximum lane change length
* Revert "remove calc maximum lane change length" This reverts commit e9cc386e1c21321c59f518d2acbe78a3c668471f. * Revert "RT1-8004 refactor sample longitudinal acc values" This reverts commit 775bcdb8fa1817511741776861f9edb7e22fd744.
- replace generateCenterLinePath
- RT1-8004 simplify stuck detection
- swap call to update filtered_objects and update transient data
- RT1-8004 fix conflict
- RT1-8004 Rename isVehicleStuck to is_ego_stuck()
* RT1-8004 change calcPrepareDuration to snake case ---------
- refactor(lane_change): refactor code using transient data
(#8997)
- add target lane length and ego arc length along current and target lanes to transient data
- refactor code using transient data
- refactor get_lane_change_paths function
- minor refactoring
- refactor util functions
* refactor getPrepareSegment function ---------
- refactor(bpp): simplify ExtendedPredictedObject and add new member
variables
(#8889)
- simplify ExtendedPredictedObject and add new member variables
- replace self polygon to initial polygon
- comment
* add comments to dist of ego ---------
- fix(lane_change): fix abort distance enough check
(#8979)
- RT1-7991 fix abort distance enough check
* RT-7991 remove unused function ---------
- refactor(lane_change): add TransientData to store commonly used
lane change-related variables.
(#8954)
- add transient data
- reverted max lc dist in calcCurrentMinMax
- rename
- minor refactoring
* update doxygen comments ---------
- feat(lane_change): modify lane change target boundary check to
consider velocity
(#8961)
- check if candidate path footprint exceeds target lane boundary when lc velocity is above minimum
- move functions to relevant module
- suppress unused function cppcheck
* minor change ---------
- fix(autoware_behavior_path_lane_change_module): fix
unusedFunction
(#8960)
- fix:unusedFunction
- fix:unusedFunction
- fix:unusedFunction
* fix:pre_commit ---------
- refactor(lane_change): refactor getLaneChangePaths function
(#8909)
- refactor lane change utility funcions
- LC utility function to get distance to next regulatory element
- don't activate LC module when close to regulatory element
- modify threshold distance calculation
- move regulatory element check to canTransitFailureState() function
- always run LC module if approaching terminal point
- use max possible LC length as threshold
- update LC readme
- refactor implementation
- update readme
- refactor checking data validity
- refactor sampling of prepare phase metrics and lane changing phase metrics
- add route handler function to get pose from 2d arc length
- refactor candidate path generation
- refactor candidate path safety check
- fix variable name
* Update planning/autoware_route_handler/src/route_handler.cpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- correct parameter name
- set prepare segment velocity after taking max path velocity value
- update LC README
- minor changes
- check phase length difference with previos valid candidate path
- change logger name
- change functions names to snake case
- use snake case for function names
* add colors to flow chart in README ---------Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>>
- refactor(autoware_interpolation): prefix package and namespace with autoware (#8088) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- feat(lane_change): add checks to ensure the edge of vehicle do not
exceed target lane boundary when changing lanes
(#8750)
- check if LC candidate path footprint exceeds target lane far bound
- add parameter to enable/disable check
- check only lane changing section of cadidate path
- fix spelling
* small refactoring ---------
- fix(lane_change): set initail rtc state properly (#8902) set initail rtc state properly
- feat(lane_change): improve execution condition of lane change
module
(#8648)
- refactor lane change utility funcions
- LC utility function to get distance to next regulatory element
- don't activate LC module when close to regulatory element
- modify threshold distance calculation
- move regulatory element check to canTransitFailureState() function
- always run LC module if approaching terminal point
- use max possible LC length as threshold
- update LC readme
- refactor implementation
- update readme
* check distance to reg element for candidate path only if not near terminal start ---------
- feat(rtc_interface, lane_change): check state transition for
cooperate status
(#8855)
- update rtc state transition
- remove transition from failuer and succeeded
- fix
- check initial state for cooperate status
* change rtc cooperate status according to module status ---------
- fix(autoware_behavior_path_planner): align the parameters with launcher (#8790) parameters in behavior_path_planner aligned
- fix(autoware_behavior_path_lane_change_module): fix unusedFunction (#8653) fix:unusedFunction
- fix(bpp): use common steering factor interface for same scene modules (#8675)
- fix(lane_change): update rtc status for some failure condition (#8604) update rtc status for some failure condition
- fix(lane_change): activate turn signal as soon as we have the
intention to change lanes
(#8571)
- modify lane change requested condition
- modify lane change requested condition
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- style(pre-commit): autofix
- fix docstring
- modify LC turn signal logic
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> * minor change ---------Co-authored-by: Muhammad Zulfaqar Azmi <<zulfaqar.azmi@tier4.jp>> Co-authored-by: Zulfaqar Azmi <<93502286+zulfaqar-azmi-t4@users.noreply.github.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(lane_change): fix delay logic that caused timing to be late
(#8549)
- RT1-5067 fix delay logic that caused timing to be late
* remove autoware namespace Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- fix(lane_change): modify lane change requested condition
(#8510)
- modify lane change requested condition
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>
- style(pre-commit): autofix
* fix docstring ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(lane_change): consider deceleration in safety check for cancel
(#7943)
- feat(lane_change): consider deceleration in safety check for cancel
- docs(lane_change): fix document
- fix conflicts and refactor
- fix conflict
* style(pre-commit): autofix ---------Co-authored-by: Muhammad Zulfaqar Azmi <<zulfaqar.azmi@tier4.jp>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- refactor(lane_change): rename prepare_segment_ignore_object_velocity_thresh (#8532) change parameter name for more expressive name
- refactor(behavior_path_planner): apply clang-tidy check
(#7549)
- goal_planner
* lane_change ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>
- feat(lane_change): ensure LC merging lane stop point is safe
(#8369)
- function to check for merging lane
- function to compute distance from last fit width center line point to lane end
- ensure lane width at LC stop point is larger than ego width
- refactor function isMergingLane
- improve implementation
- apply logic only when current ego foot print is within lane
- change implementation to use intersection points of buffered centerline and lane polygon
- minor refactoring
* overload function isEgoWithinOriginalLane to pass lane polygon directly ---------
- refactor(lane_change): update filtered objects only once (#8489)
- fix(lane_change): moving object is filtered in the extended target
lanes
(#8218)
- object 3rd
* named param ---------
- fix(lane_change): do not cancel when approaching terminal start
(#8381)
- do not cancel if ego vehicle approaching terminal start
- Insert stop point if object is coming from rear
- minor edit to fix conflict
* rename function ---------
- fix(lane_change): fix invalid doesn't have stop point (#8470) fix invalid doesn't have stop point
- fix(lane_change): unify stuck detection to avoid unnecessary computation (#8383) unify stuck detection in getLaneChangePaths
- fix(turn_signal, lane_change, goal_planner): add optional to
tackle lane change turn signal and pull over turn signal
(#8463)
- add optional to tackle LC turn signal and pull over turn signal
* CPP file should not re-define default value; typo in copying from internal repos ---------
- refactor(lane_change): separate leading and trailing objects
(#8214)
- refactor(lane_change): separate leading and trailing objects
* Refactor to use common function ---------
- fix(lane_change): skip generating path if longitudinal distance
difference is less than threshold
(#8363)
- fix when prepare length is insufficient
* add reason for comparing prev_prep_diff with eps for lc_length_diff ---------
- fix(lane_change): skip generating path if lane changing path is too long (#8362) rework. skip lane changing for insufficeient distance in target lane
- fix(lane_change): skip path computation if len exceed dist to terminal start (#8359) Skip computation if prepare length exceed distance to terminal start
- refactor(lane_change): refactor debug print when computing paths (#8358) Refactor debug print
- chore(lane_change): add codeowner (#8387)
- refactor(lane_change): check start point directly after getting
start point
(#8357)
- check start point directly after getting start point
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- feat(lane_change): use different rss param to deal with parked
vehicle
(#8316)
- different rss value for parked vehicle
* Documentation and config file update ---------
- fix(lane_change): relax finish judge
(#8133)
- fix(lane_change): relax finish judge
- documentation update
- update readme explanations
* update config ---------
- feat(lane_change): force deactivation in prepare phase (#8235) transfer to cancel state when force deactivated
- fix(autoware_behavior_path_lane_change_module): fix passedByValue (#8208) fix:passedByValue
- fix(lane_change): filtering object ahead of terminal
(#8093)
- employ lanelet based filtering before distance based filtering
- use distance based to terminal check instead
- remove RCLCPP INFO
* update flow chart ---------
- fix(lane_change): delay lane change cancel (#8048) RT1-6955: delay lane change cancel
- feat(lane_change): enable force execution under unsafe conditions (#8131) add force execution conditions
- refactor(lane_change): update lanes and its polygons only when
it's updated
(#7989)
- refactor(lane_change): compute lanes and polygon only when updated
* Revert accidental changesd This reverts commit cbfd9ae8a88b2d6c3b27b35c9a08bb824ecd5011.
- fix spell check
- Make a common getter for current lanes
- add target lanes getter
* some minor function refactoring ---------
- feat(autoware_behavior_path_planner_common,autoware_behavior_path_lane_change_module):
add time_keeper to bpp
(#8004)
- feat(autoware_behavior_path_planner_common,autoware_behavior_path_lane_change_module): add time_keeper to bpp
* update
- fix(autoware_behavior_path_lane_change_module): fix shadowVariable (#7964) fix:shadowVariable
- refactor(lane_change): move struct to lane change namespace
(#7841)
- move struct to lane change namespace
* Revert "move struct to lane change namespace" This reverts commit 306984a76103c427732f170a6f7eb5f94e895b0b. ---------
- feat: add [autoware_]{.title-ref} prefix to [lanelet2_extension]{.title-ref} (#7640)
- fix(lane_change): prevent empty path when rerouting (#7717) fix(lane_change): prevent empty path when routing
- feat(start_planner): yaw threshold for rss check
(#7657)
- add param to customize yaw th
- add param to other modules
- docs
- update READMEs with params
- fix LC README
* use normalized yaw diff ---------
- refactor(lane_change): use lane change namespace for structs
(#7508)
- refactor(lane_change): use lane change namespace for structs
* Move lane change namespace to bottom level ---------
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- refactor(route_handler)!: rename to include/autoware/{package_name} (#7530) refactor(route_handler)!: rename to include/autoware/{package_name}
- refactor(behaivor_path_planner)!: rename to
include/autoware/{package_name}
(#7522)
- refactor(behavior_path_planner)!: make autoware dir in include
- refactor(start_planner): make autoware include dir
- refactor(goal_planner): make autoware include dir
- sampling planner module
- fix sampling planner build
- dynamic_avoidance
- lc
- side shift
- autoware_behavior_path_static_obstacle_avoidance_module
- autoware_behavior_path_planner_common
- make behavior_path dir
- pre-commit
- fix pre-commit
* fix build ---------
- Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, Kosuke Takeuchi, Mamoru Sobue, Satoshi OTA, T-Kimura-MM, Takayuki Murooka, Yukinari Hisaki, Yutaka Kondo, Yuxuan Liu, Zhe Shen, Zulfaqar Azmi, danielsanchezaran, kobayu858, mkquda