Skip to content

Commit f4accdc

Browse files
committed
feat(avoidance): return original lane as soon as possible if traffic is congested
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent f1deb04 commit f4accdc

File tree

7 files changed

+49
-9
lines changed

7 files changed

+49
-9
lines changed

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -228,6 +228,9 @@
228228
traffic_light:
229229
enable: true # [-]
230230
buffer: 3.0 # [m]
231+
traffic_jam:
232+
enable: true # [-]
233+
buffer: 8.0 # [m]
231234

232235
# For cancel maneuver
233236
cancel:

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -135,10 +135,12 @@ struct AvoidanceParameters
135135
// consider avoidance return dead line
136136
bool enable_dead_line_for_goal{false};
137137
bool enable_dead_line_for_traffic_light{false};
138+
bool enable_dead_line_for_traffic_jam{false};
138139

139140
// module try to return original path to keep this distance from edge point of the path.
140141
double dead_line_buffer_for_goal{0.0};
141142
double dead_line_buffer_for_traffic_light{0.0};
143+
double dead_line_buffer_for_traffic_jam{0.0};
142144

143145
// max deceleration for
144146
double max_deceleration{0.0};

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -281,9 +281,13 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
281281
p.enable_dead_line_for_goal = getOrDeclareParameter<bool>(*node, ns + "goal.enable");
282282
p.enable_dead_line_for_traffic_light =
283283
getOrDeclareParameter<bool>(*node, ns + "traffic_light.enable");
284+
p.enable_dead_line_for_traffic_jam =
285+
getOrDeclareParameter<bool>(*node, ns + "traffic_jam.enable");
284286
p.dead_line_buffer_for_goal = getOrDeclareParameter<double>(*node, ns + "goal.buffer");
285287
p.dead_line_buffer_for_traffic_light =
286288
getOrDeclareParameter<double>(*node, ns + "traffic_light.buffer");
289+
p.dead_line_buffer_for_traffic_jam =
290+
getOrDeclareParameter<double>(*node, ns + "traffic_jam.buffer");
287291
}
288292

289293
// cancel

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -167,7 +167,7 @@ DrivableLanes generateExpandedDrivableLanes(
167167

168168
double calcDistanceToReturnDeadLine(
169169
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
170-
const std::shared_ptr<const PlannerData> & planner_data,
170+
ObjectDataArray & other_objects, const std::shared_ptr<const PlannerData> & planner_data,
171171
const std::shared_ptr<AvoidanceParameters> & parameters);
172172

173173
double calcDistanceToAvoidStartLine(

planning/behavior_path_avoidance_module/schema/avoidance.schema.json

+18-1
Original file line numberDiff line numberDiff line change
@@ -1183,9 +1183,26 @@
11831183
},
11841184
"required": ["enable", "buffer"],
11851185
"additionalProperties": false
1186+
},
1187+
"traffic_jam": {
1188+
"type": "object",
1189+
"properties": {
1190+
"enable": {
1191+
"type": "boolean",
1192+
"description": "Insert stop point in order to return original lane before reaching vehicles in traffic jam.",
1193+
"default": "true"
1194+
},
1195+
"buffer": {
1196+
"type": "number",
1197+
"description": "Buffer distance to return original lane before reaching vehicles in traffic jam.",
1198+
"default": 8.0
1199+
}
1200+
},
1201+
"required": ["enable", "buffer"],
1202+
"additionalProperties": false
11861203
}
11871204
},
1188-
"required": ["goal", "traffic_light"],
1205+
"required": ["goal", "traffic_light", "traffic_jam"],
11891206
"additionalProperties": false
11901207
}
11911208
},

planning/behavior_path_avoidance_module/src/scene.cpp

+11-6
Original file line numberDiff line numberDiff line change
@@ -271,12 +271,6 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
271271
data.reference_path, 0, data.reference_path.points.size(),
272272
motion_utils::calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0));
273273

274-
data.to_return_point = utils::avoidance::calcDistanceToReturnDeadLine(
275-
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);
276-
277-
data.to_start_point = utils::avoidance::calcDistanceToAvoidStartLine(
278-
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);
279-
280274
// target objects for avoidance
281275
fillAvoidanceTargetObjects(data, debug);
282276

@@ -290,6 +284,17 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
290284
return a.longitudinal < b.longitudinal;
291285
});
292286

287+
std::sort(data.other_objects.begin(), data.other_objects.end(), [](auto a, auto b) {
288+
return a.longitudinal < b.longitudinal;
289+
});
290+
291+
data.to_return_point = utils::avoidance::calcDistanceToReturnDeadLine(
292+
data.current_lanelets, data.reference_path_rough, data.other_objects, planner_data_,
293+
parameters_);
294+
295+
data.to_start_point = utils::avoidance::calcDistanceToAvoidStartLine(
296+
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);
297+
293298
// set base path
294299
path_shifter_.setPath(data.reference_path);
295300
}

planning/behavior_path_avoidance_module/src/utils.cpp

+10-1
Original file line numberDiff line numberDiff line change
@@ -2355,7 +2355,7 @@ double calcDistanceToAvoidStartLine(
23552355

23562356
double calcDistanceToReturnDeadLine(
23572357
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path,
2358-
const std::shared_ptr<const PlannerData> & planner_data,
2358+
ObjectDataArray & other_objects, const std::shared_ptr<const PlannerData> & planner_data,
23592359
const std::shared_ptr<AvoidanceParameters> & parameters)
23602360
{
23612361
if (lanelets.empty()) {
@@ -2374,6 +2374,15 @@ double calcDistanceToReturnDeadLine(
23742374
}
23752375
}
23762376

2377+
// dead line stop factor(traffic jam)
2378+
if (parameters->enable_dead_line_for_traffic_jam && !other_objects.empty()) {
2379+
if (filtering_utils::isOnEgoLane(other_objects.front())) {
2380+
distance_to_return_dead_line = std::min(
2381+
distance_to_return_dead_line,
2382+
other_objects.front().longitudinal - parameters->dead_line_buffer_for_traffic_jam);
2383+
}
2384+
}
2385+
23772386
// dead line for goal
23782387
if (
23792388
!utils::isAllowedGoalModification(planner_data->route_handler) &&

0 commit comments

Comments
 (0)