Skip to content

Commit 1c5ca20

Browse files
authoredOct 15, 2023
feat(lane_change): add rss paramas for stuck (#5300)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent d1a77d5 commit 1c5ca20

File tree

6 files changed

+51
-12
lines changed

6 files changed

+51
-12
lines changed
 

‎planning/behavior_path_planner/config/lane_change/lane_change.param.yaml

+8
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,14 @@
4545
lateral_distance_max_threshold: 1.0
4646
longitudinal_distance_min_threshold: 2.5
4747
longitudinal_velocity_delta_time: 0.6
48+
stuck:
49+
expected_front_deceleration: -1.0
50+
expected_rear_deceleration: -1.0
51+
rear_vehicle_reaction_time: 2.0
52+
rear_vehicle_safety_time_margin: 1.0
53+
lateral_distance_max_threshold: 2.0
54+
longitudinal_distance_min_threshold: 3.0
55+
longitudinal_velocity_delta_time: 0.8
4856

4957
# lane expansion for object filtering
5058
lane_expansion:

‎planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -230,7 +230,8 @@ class LaneChangeBase
230230
virtual bool getLaneChangePaths(
231231
const lanelet::ConstLanelets & original_lanelets,
232232
const lanelet::ConstLanelets & target_lanelets, Direction direction,
233-
LaneChangePaths * candidate_paths, const bool check_safety) const = 0;
233+
LaneChangePaths * candidate_paths, const utils::path_safety_checker::RSSparams rss_params,
234+
const bool is_stuck, const bool check_safety) const = 0;
234235

235236
virtual TurnSignalInfo calcTurnSignalInfo() = 0;
236237

‎planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,7 @@ class NormalLaneChange : public LaneChangeBase
138138
bool getLaneChangePaths(
139139
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
140140
Direction direction, LaneChangePaths * candidate_paths,
141+
const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
141142
const bool check_safety = true) const override;
142143

143144
TurnSignalInfo calcTurnSignalInfo() override;
@@ -146,7 +147,7 @@ class NormalLaneChange : public LaneChangeBase
146147

147148
PathSafetyStatus isLaneChangePathSafe(
148149
const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects,
149-
const utils::path_safety_checker::RSSparams & rss_params,
150+
const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck,
150151
CollisionCheckDebugMap & debug_data) const;
151152

152153
LaneChangeTargetObjectIndices filterObject(

‎planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,7 @@ struct LaneChangeParameters
8585
bool allow_loose_check_for_cancel{true};
8686
utils::path_safety_checker::RSSparams rss_params{};
8787
utils::path_safety_checker::RSSparams rss_params_for_abort{};
88+
utils::path_safety_checker::RSSparams rss_params_for_stuck{};
8889

8990
// abort
9091
LaneChangeCancelParameters cancel{};

‎planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp

+15
Original file line numberDiff line numberDiff line change
@@ -128,6 +128,21 @@ LaneChangeModuleManager::LaneChangeModuleManager(
128128
p.rss_params_for_abort.lateral_distance_max_threshold = getOrDeclareParameter<double>(
129129
*node, parameter("safety_check.cancel.lateral_distance_max_threshold"));
130130

131+
p.rss_params_for_stuck.longitudinal_distance_min_threshold = getOrDeclareParameter<double>(
132+
*node, parameter("safety_check.stuck.longitudinal_distance_min_threshold"));
133+
p.rss_params_for_stuck.longitudinal_velocity_delta_time = getOrDeclareParameter<double>(
134+
*node, parameter("safety_check.stuck.longitudinal_velocity_delta_time"));
135+
p.rss_params_for_stuck.front_vehicle_deceleration = getOrDeclareParameter<double>(
136+
*node, parameter("safety_check.stuck.expected_front_deceleration"));
137+
p.rss_params_for_stuck.rear_vehicle_deceleration = getOrDeclareParameter<double>(
138+
*node, parameter("safety_check.stuck.expected_rear_deceleration"));
139+
p.rss_params_for_stuck.rear_vehicle_reaction_time = getOrDeclareParameter<double>(
140+
*node, parameter("safety_check.stuck.rear_vehicle_reaction_time"));
141+
p.rss_params_for_stuck.rear_vehicle_safety_time_margin = getOrDeclareParameter<double>(
142+
*node, parameter("safety_check.stuck.rear_vehicle_safety_time_margin"));
143+
p.rss_params_for_stuck.lateral_distance_max_threshold = getOrDeclareParameter<double>(
144+
*node, parameter("safety_check.stuck.lateral_distance_max_threshold"));
145+
131146
// target object
132147
{
133148
std::string ns = "lane_change.target_object.";

‎planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp

+23-10
Original file line numberDiff line numberDiff line change
@@ -83,8 +83,17 @@ std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path)
8383

8484
// find candidate paths
8585
LaneChangePaths valid_paths{};
86-
const auto found_safe_path =
87-
getLaneChangePaths(current_lanes, target_lanes, direction_, &valid_paths);
86+
const bool is_stuck = isVehicleStuckByObstacle(current_lanes);
87+
bool found_safe_path = getLaneChangePaths(
88+
current_lanes, target_lanes, direction_, &valid_paths, lane_change_parameters_->rss_params,
89+
is_stuck);
90+
// if no safe path is found and ego is stuck, try to find a path with a small margin
91+
if (!found_safe_path && is_stuck) {
92+
found_safe_path = getLaneChangePaths(
93+
current_lanes, target_lanes, direction_, &valid_paths,
94+
lane_change_parameters_->rss_params_for_stuck, is_stuck);
95+
}
96+
8897
debug_valid_path_ = valid_paths;
8998

9099
if (valid_paths.empty()) {
@@ -1006,7 +1015,9 @@ bool NormalLaneChange::hasEnoughLengthToIntersection(
10061015

10071016
bool NormalLaneChange::getLaneChangePaths(
10081017
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
1009-
Direction direction, LaneChangePaths * candidate_paths, const bool check_safety) const
1018+
Direction direction, LaneChangePaths * candidate_paths,
1019+
const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
1020+
const bool check_safety) const
10101021
{
10111022
object_debug_.clear();
10121023
if (current_lanes.empty() || target_lanes.empty()) {
@@ -1237,9 +1248,11 @@ bool NormalLaneChange::getLaneChangePaths(
12371248
}
12381249

12391250
candidate_paths->push_back(*candidate_path);
1240-
if (utils::lane_change::passParkedObject(
1241-
route_handler, *candidate_path, target_objects.target_lane, lane_change_buffer,
1242-
is_goal_in_route, *lane_change_parameters_, object_debug_)) {
1251+
if (
1252+
!is_stuck &&
1253+
utils::lane_change::passParkedObject(
1254+
route_handler, *candidate_path, target_objects.target_lane, lane_change_buffer,
1255+
is_goal_in_route, *lane_change_parameters_, object_debug_)) {
12431256
return false;
12441257
}
12451258

@@ -1248,7 +1261,7 @@ bool NormalLaneChange::getLaneChangePaths(
12481261
}
12491262

12501263
const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe(
1251-
*candidate_path, target_objects, lane_change_parameters_->rss_params, object_debug_);
1264+
*candidate_path, target_objects, rss_params, is_stuck, object_debug_);
12521265

12531266
if (is_safe) {
12541267
return true;
@@ -1270,8 +1283,9 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
12701283
debug_filtered_objects_ = target_objects;
12711284

12721285
CollisionCheckDebugMap debug_data;
1286+
const bool is_stuck = isVehicleStuckByObstacle(current_lanes);
12731287
const auto safety_status = isLaneChangePathSafe(
1274-
path, target_objects, lane_change_parameters_->rss_params_for_abort, debug_data);
1288+
path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data);
12751289
{
12761290
// only for debug purpose
12771291
object_debug_.clear();
@@ -1528,7 +1542,7 @@ bool NormalLaneChange::getAbortPath()
15281542

15291543
PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
15301544
const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects,
1531-
const utils::path_safety_checker::RSSparams & rss_params,
1545+
const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck,
15321546
CollisionCheckDebugMap & debug_data) const
15331547
{
15341548
PathSafetyStatus path_safety_status;
@@ -1552,7 +1566,6 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
15521566

15531567
auto collision_check_objects = target_objects.target_lane;
15541568
const auto current_lanes = getCurrentLanes();
1555-
const auto is_stuck = isVehicleStuckByObstacle(current_lanes);
15561569

15571570
if (lane_change_parameters_->check_objects_on_current_lanes || is_stuck) {
15581571
collision_check_objects.insert(

0 commit comments

Comments
 (0)