Skip to content

Commit 3d27146

Browse files
committed
refactor(static_obstacle_avoidance): organize params for drivable lane (autowarefoundation#7715)
* refactor(static_obstacle_avoidance): organize params for drivable lane Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 32f3c9a commit 3d27146

File tree

5 files changed

+22
-26
lines changed

5 files changed

+22
-26
lines changed

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+6-2
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,13 @@
55
resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER
66
resample_interval_for_output: 4.0 # [m] FOR DEVELOPER
77

8+
# drivable lane setting. this module is able to use not only current lane but also right/left lane
9+
# if the current lane(=lanelet::Lanelet) and the right/left lane share the boundary(=lanelet::Linestring) in HDMap.
10+
# "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object.
11+
# "same_direction_lane" : this module uses same direction lane to avoid object if need.
12+
# "opposite_direction_lane": this module uses both same direction and opposite direction lane.
13+
use_lane_type: "opposite_direction_lane"
814
# drivable area setting
9-
use_adjacent_lane: true
10-
use_opposite_lane: true
1115
use_intersection_areas: true
1216
use_hatched_road_markings: true
1317
use_freespace_areas: true

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+2-6
Original file line numberDiff line numberDiff line change
@@ -101,12 +101,8 @@ struct AvoidanceParameters
101101
// computational cost for latter modules.
102102
double resample_interval_for_output = 3.0;
103103

104-
// enable avoidance to be perform only in lane with same direction
105-
bool use_adjacent_lane{true};
106-
107-
// enable avoidance to be perform in opposite lane direction
108-
// to use this, enable_avoidance_over_same_direction need to be set to true.
109-
bool use_opposite_lane{true};
104+
// drivable lane config
105+
std::string use_lane_type{"current_lane"};
110106

111107
// if this param is true, it reverts avoidance path when the path is no longer needed.
112108
bool enable_cancel_maneuver{false};

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
4646
// drivable area
4747
{
4848
const std::string ns = "avoidance.";
49-
p.use_adjacent_lane = getOrDeclareParameter<bool>(*node, ns + "use_adjacent_lane");
50-
p.use_opposite_lane = getOrDeclareParameter<bool>(*node, ns + "use_opposite_lane");
49+
p.use_lane_type = getOrDeclareParameter<std::string>(*node, ns + "use_lane_type");
5150
p.use_intersection_areas = getOrDeclareParameter<bool>(*node, ns + "use_intersection_areas");
5251
p.use_hatched_road_markings =
5352
getOrDeclareParameter<bool>(*node, ns + "use_hatched_road_markings");

planning/behavior_path_avoidance_module/schema/avoidance.schema.json

+6-11
Original file line numberDiff line numberDiff line change
@@ -22,15 +22,11 @@
2222
"description": "Path generation method.",
2323
"default": "shift_line_base"
2424
},
25-
"use_adjacent_lane": {
26-
"type": "boolean",
27-
"description": "Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane.",
28-
"default": "true"
29-
},
30-
"use_opposite_lane": {
31-
"type": "boolean",
32-
"description": "Extend avoidance trajectory to opposite direction lane. `use_adjacent_lane` must be `true` to take effects.",
33-
"default": "true"
25+
"use_lane_type": {
26+
"type": "string",
27+
"enum": ["current_lane", "same_direction_lane", "opposite_direction_lane"],
28+
"description": "Drivable lane configuration.",
29+
"default": "opposite_direction_lane"
3430
},
3531
"use_hatched_road_markings": {
3632
"type": "boolean",
@@ -1475,8 +1471,7 @@
14751471
"resample_interval_for_planning",
14761472
"resample_interval_for_output",
14771473
"path_generation_method",
1478-
"use_adjacent_lane",
1479-
"use_opposite_lane",
1474+
"use_lane_type",
14801475
"use_hatched_road_markings",
14811476
"use_intersection_areas",
14821477
"use_freespace_areas",

planning/behavior_path_avoidance_module/src/utils.cpp

+7-5
Original file line numberDiff line numberDiff line change
@@ -2318,14 +2318,16 @@ DrivableLanes generateExpandedDrivableLanes(
23182318
current_drivable_lanes.left_lane = lanelet;
23192319
current_drivable_lanes.right_lane = lanelet;
23202320

2321-
if (!parameters->use_adjacent_lane) {
2321+
if (parameters->use_lane_type == "current_lane") {
23222322
return current_drivable_lanes;
23232323
}
23242324

2325+
const auto use_opposite_lane = parameters->use_lane_type == "opposite_direction_lane";
2326+
23252327
// 1. get left/right side lanes
23262328
const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
2327-
const auto all_left_lanelets = route_handler->getAllLeftSharedLinestringLanelets(
2328-
target_lane, parameters->use_opposite_lane, true);
2329+
const auto all_left_lanelets =
2330+
route_handler->getAllLeftSharedLinestringLanelets(target_lane, use_opposite_lane, true);
23292331
if (!all_left_lanelets.empty()) {
23302332
current_drivable_lanes.left_lane = all_left_lanelets.back(); // leftmost lanelet
23312333
pushUniqueVector(
@@ -2334,8 +2336,8 @@ DrivableLanes generateExpandedDrivableLanes(
23342336
}
23352337
};
23362338
const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
2337-
const auto all_right_lanelets = route_handler->getAllRightSharedLinestringLanelets(
2338-
target_lane, parameters->use_opposite_lane, true);
2339+
const auto all_right_lanelets =
2340+
route_handler->getAllRightSharedLinestringLanelets(target_lane, use_opposite_lane, true);
23392341
if (!all_right_lanelets.empty()) {
23402342
current_drivable_lanes.right_lane = all_right_lanelets.back(); // rightmost lanelet
23412343
pushUniqueVector(

0 commit comments

Comments
 (0)