Skip to content

Commit f07fa8e

Browse files
feat(lane_change): use different rss param to deal with parked vehicle (#8316)
* different rss value for parked vehicle Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Documentation and config file update Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 43439ac commit f07fa8e

File tree

5 files changed

+44
-1
lines changed

5 files changed

+44
-1
lines changed

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md

+12
Original file line numberDiff line numberDiff line change
@@ -773,6 +773,18 @@ The following parameters are used to judge lane change completion.
773773
| `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 |
774774
| `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.8 |
775775

776+
#### safety constraints specifically for stopped or parked vehicles
777+
778+
| Name | Unit | Type | Description | Default value |
779+
| :-------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
780+
| `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 |
781+
| `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 |
782+
| `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 |
783+
| `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 |
784+
| `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 |
785+
| `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 |
786+
| `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 |
787+
776788
##### safety constraints to cancel lane change path
777789

778790
| Name | Unit | Type | Description | Default value |

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml

+8
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,14 @@
3838
lateral_distance_max_threshold: 2.0
3939
longitudinal_distance_min_threshold: 3.0
4040
longitudinal_velocity_delta_time: 0.8
41+
parked:
42+
expected_front_deceleration: -1.0
43+
expected_rear_deceleration: -2.0
44+
rear_vehicle_reaction_time: 1.0
45+
rear_vehicle_safety_time_margin: 0.8
46+
lateral_distance_max_threshold: 1.0
47+
longitudinal_distance_min_threshold: 3.0
48+
longitudinal_velocity_delta_time: 0.0
4149
cancel:
4250
expected_front_deceleration: -1.0
4351
expected_rear_deceleration: -2.0

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -151,6 +151,7 @@ struct Parameters
151151
bool allow_loose_check_for_cancel{true};
152152
double collision_check_yaw_diff_threshold{3.1416};
153153
utils::path_safety_checker::RSSparams rss_params{};
154+
utils::path_safety_checker::RSSparams rss_params_for_parked{};
154155
utils::path_safety_checker::RSSparams rss_params_for_abort{};
155156
utils::path_safety_checker::RSSparams rss_params_for_stuck{};
156157

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp

+17
Original file line numberDiff line numberDiff line change
@@ -122,6 +122,23 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
122122
p.rss_params.lateral_distance_max_threshold = getOrDeclareParameter<double>(
123123
*node, parameter("safety_check.execution.lateral_distance_max_threshold"));
124124

125+
p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
126+
*node, parameter("safety_check.parked.longitudinal_distance_min_threshold"));
127+
p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
128+
*node, parameter("safety_check.parked.longitudinal_distance_min_threshold"));
129+
p.rss_params_for_parked.longitudinal_velocity_delta_time = getOrDeclareParameter<double>(
130+
*node, parameter("safety_check.parked.longitudinal_velocity_delta_time"));
131+
p.rss_params_for_parked.front_vehicle_deceleration = getOrDeclareParameter<double>(
132+
*node, parameter("safety_check.parked.expected_front_deceleration"));
133+
p.rss_params_for_parked.rear_vehicle_deceleration = getOrDeclareParameter<double>(
134+
*node, parameter("safety_check.parked.expected_rear_deceleration"));
135+
p.rss_params_for_parked.rear_vehicle_reaction_time = getOrDeclareParameter<double>(
136+
*node, parameter("safety_check.parked.rear_vehicle_reaction_time"));
137+
p.rss_params_for_parked.rear_vehicle_safety_time_margin = getOrDeclareParameter<double>(
138+
*node, parameter("safety_check.parked.rear_vehicle_safety_time_margin"));
139+
p.rss_params_for_parked.lateral_distance_max_threshold = getOrDeclareParameter<double>(
140+
*node, parameter("safety_check.parked.lateral_distance_max_threshold"));
141+
125142
p.rss_params_for_abort.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
126143
*node, parameter("safety_check.cancel.longitudinal_distance_min_threshold"));
127144
p.rss_params_for_abort.longitudinal_velocity_delta_time = getOrDeclareParameter<double>(

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -2082,9 +2082,14 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
20822082
const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj(
20832083
obj, lane_change_parameters_->use_all_predicted_path);
20842084
auto is_safe = true;
2085+
const auto selected_rss_param =
2086+
(obj.initial_twist.twist.linear.x <=
2087+
lane_change_parameters_->prepare_segment_ignore_object_velocity_thresh)
2088+
? lane_change_parameters_->rss_params_for_parked
2089+
: rss_params;
20852090
for (const auto & obj_path : obj_predicted_paths) {
20862091
const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons(
2087-
path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0,
2092+
path, ego_predicted_path, obj, obj_path, common_parameters, selected_rss_param, 1.0,
20882093
get_max_velocity_for_safety_check(), collision_check_yaw_diff_threshold,
20892094
current_debug_data.second);
20902095

0 commit comments

Comments
 (0)