Skip to content

Commit 682a814

Browse files
authored
refactor(avoidance): unify redundant parameters (#6798)
* refactor(avoidance): unify redundant parameters Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor(avoidance): remove unused parameters Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 8793584 commit 682a814

File tree

6 files changed

+29
-68
lines changed

6 files changed

+29
-68
lines changed

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+2-8
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,6 @@
2828
hard_margin_for_parked_vehicle: 0.7 # [m]
2929
max_expand_ratio: 0.0 # [-] FOR DEVELOPER
3030
envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER
31-
use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
3231
truck:
3332
th_moving_speed: 1.0
3433
th_moving_time: 2.0
@@ -39,7 +38,6 @@
3938
hard_margin_for_parked_vehicle: 0.7
4039
max_expand_ratio: 0.0
4140
envelope_buffer_margin: 0.5
42-
use_conservative_buffer_longitudinal: true
4341
bus:
4442
th_moving_speed: 1.0
4543
th_moving_time: 2.0
@@ -50,7 +48,6 @@
5048
hard_margin_for_parked_vehicle: 0.7
5149
max_expand_ratio: 0.0
5250
envelope_buffer_margin: 0.5
53-
use_conservative_buffer_longitudinal: true
5451
trailer:
5552
th_moving_speed: 1.0
5653
th_moving_time: 2.0
@@ -61,7 +58,6 @@
6158
hard_margin_for_parked_vehicle: 0.7
6259
max_expand_ratio: 0.0
6360
envelope_buffer_margin: 0.5
64-
use_conservative_buffer_longitudinal: true
6561
unknown:
6662
th_moving_speed: 0.28
6763
th_moving_time: 1.0
@@ -72,7 +68,6 @@
7268
hard_margin_for_parked_vehicle: -0.2
7369
max_expand_ratio: 0.0
7470
envelope_buffer_margin: 0.1
75-
use_conservative_buffer_longitudinal: true
7671
bicycle:
7772
th_moving_speed: 0.28
7873
th_moving_time: 1.0
@@ -83,7 +78,6 @@
8378
hard_margin_for_parked_vehicle: 0.5
8479
max_expand_ratio: 0.0
8580
envelope_buffer_margin: 0.5
86-
use_conservative_buffer_longitudinal: true
8781
motorcycle:
8882
th_moving_speed: 1.0
8983
th_moving_time: 1.0
@@ -94,7 +88,6 @@
9488
hard_margin_for_parked_vehicle: 0.3
9589
max_expand_ratio: 0.0
9690
envelope_buffer_margin: 0.5
97-
use_conservative_buffer_longitudinal: true
9891
pedestrian:
9992
th_moving_speed: 0.28
10093
th_moving_time: 1.0
@@ -105,7 +98,6 @@
10598
hard_margin_for_parked_vehicle: 0.5
10699
max_expand_ratio: 0.0
107100
envelope_buffer_margin: 0.5
108-
use_conservative_buffer_longitudinal: true
109101
lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER
110102
upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER
111103

@@ -222,6 +214,8 @@
222214
min_slow_down_speed: 1.38 # [m/s]
223215
buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER
224216
nominal_avoidance_speed: 8.33 # [m/s] FOR DEVELOPER
217+
consider_front_overhang: true # [-]
218+
consider_rear_overhang: true # [-]
225219
# return dead line
226220
return_dead_line:
227221
goal:

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+3-10
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,6 @@ struct ObjectParameter
7676
double lateral_hard_margin_for_parked_vehicle{1.0};
7777

7878
double longitudinal_margin{0.0};
79-
80-
bool use_conservative_buffer_longitudinal{true};
8179
};
8280

8381
struct AvoidanceParameters
@@ -191,14 +189,6 @@ struct AvoidanceParameters
191189
double time_threshold_for_ambiguous_vehicle{0.0};
192190
double distance_threshold_for_ambiguous_vehicle{0.0};
193191

194-
// when complete avoidance motion, there is a distance margin with the object
195-
// for longitudinal direction
196-
double longitudinal_collision_margin_min_distance{0.0};
197-
198-
// when complete avoidance motion, there is a time margin with the object
199-
// for longitudinal direction
200-
double longitudinal_collision_margin_time{0.0};
201-
202192
// parameters for safety check area
203193
bool enable_safety_check{false};
204194
bool check_current_lane{false};
@@ -219,6 +209,9 @@ struct AvoidanceParameters
219209
size_t hysteresis_factor_safe_count;
220210
double hysteresis_factor_expand_rate{0.0};
221211

212+
bool consider_front_overhang{true};
213+
bool consider_rear_overhang{true};
214+
222215
// maximum stop distance
223216
double stop_max_distance{0.0};
224217

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -148,16 +148,19 @@ class AvoidanceHelper
148148
{
149149
const auto object_type = utils::getHighestProbLabel(object.object.classification);
150150
const auto object_parameter = parameters_->object_parameters.at(object_type);
151-
const auto & additional_buffer_longitudinal =
152-
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
153-
: 0.0;
154-
return object_parameter.longitudinal_margin + additional_buffer_longitudinal;
151+
if (!parameters_->consider_front_overhang) {
152+
return object_parameter.longitudinal_margin;
153+
}
154+
return object_parameter.longitudinal_margin + data_->parameters.base_link2front;
155155
}
156156

157157
double getRearConstantDistance(const ObjectData & object) const
158158
{
159159
const auto object_type = utils::getHighestProbLabel(object.object.classification);
160160
const auto object_parameter = parameters_->object_parameters.at(object_type);
161+
if (!parameters_->consider_rear_overhang) {
162+
return object_parameter.longitudinal_margin;
163+
}
161164
return object_parameter.longitudinal_margin + data_->parameters.base_link2rear + object.length;
162165
}
163166

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
7070
param.lateral_hard_margin_for_parked_vehicle =
7171
getOrDeclareParameter<double>(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle");
7272
param.longitudinal_margin = getOrDeclareParameter<double>(*node, ns + "longitudinal_margin");
73-
param.use_conservative_buffer_longitudinal =
74-
getOrDeclareParameter<bool>(*node, ns + "use_conservative_buffer_longitudinal");
7573
return param;
7674
};
7775

@@ -270,6 +268,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
270268
p.buf_slow_down_speed = getOrDeclareParameter<double>(*node, ns + "buf_slow_down_speed");
271269
p.nominal_avoidance_speed =
272270
getOrDeclareParameter<double>(*node, ns + "nominal_avoidance_speed");
271+
p.consider_front_overhang = getOrDeclareParameter<bool>(*node, ns + "consider_front_overhang");
272+
p.consider_rear_overhang = getOrDeclareParameter<bool>(*node, ns + "consider_rear_overhang");
273273
}
274274

275275
// avoidance maneuver (return shift dead line)

planning/behavior_path_avoidance_module/schema/avoidance.schema.json

+13-41
Original file line numberDiff line numberDiff line change
@@ -104,11 +104,6 @@
104104
"type": "number",
105105
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
106106
"default": 0.0
107-
},
108-
"use_conservative_buffer_longitudinal": {
109-
"type": "boolean",
110-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
111-
"default": "true"
112107
}
113108
},
114109
"required": [
@@ -171,11 +166,6 @@
171166
"type": "number",
172167
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
173168
"default": 0.0
174-
},
175-
"use_conservative_buffer_longitudinal": {
176-
"type": "boolean",
177-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
178-
"default": "true"
179169
}
180170
},
181171
"required": [
@@ -238,11 +228,6 @@
238228
"type": "number",
239229
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
240230
"default": 0.0
241-
},
242-
"use_conservative_buffer_longitudinal": {
243-
"type": "boolean",
244-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
245-
"default": "true"
246231
}
247232
},
248233
"required": [
@@ -305,11 +290,6 @@
305290
"type": "number",
306291
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
307292
"default": 0.0
308-
},
309-
"use_conservative_buffer_longitudinal": {
310-
"type": "boolean",
311-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
312-
"default": "true"
313293
}
314294
},
315295
"required": [
@@ -372,11 +352,6 @@
372352
"type": "number",
373353
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
374354
"default": 0.0
375-
},
376-
"use_conservative_buffer_longitudinal": {
377-
"type": "boolean",
378-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
379-
"default": "true"
380355
}
381356
},
382357
"required": [
@@ -439,11 +414,6 @@
439414
"type": "number",
440415
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
441416
"default": 0.0
442-
},
443-
"use_conservative_buffer_longitudinal": {
444-
"type": "boolean",
445-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
446-
"default": "true"
447417
}
448418
},
449419
"required": [
@@ -506,11 +476,6 @@
506476
"type": "number",
507477
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
508478
"default": 0.0
509-
},
510-
"use_conservative_buffer_longitudinal": {
511-
"type": "boolean",
512-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
513-
"default": "true"
514479
}
515480
},
516481
"required": [
@@ -573,11 +538,6 @@
573538
"type": "number",
574539
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
575540
"default": 0.0
576-
},
577-
"use_conservative_buffer_longitudinal": {
578-
"type": "boolean",
579-
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
580-
"default": "true"
581541
}
582542
},
583543
"required": [
@@ -1150,6 +1110,16 @@
11501110
"type": "number",
11511111
"description": "Nominal avoidance speed.",
11521112
"default": 8.33
1113+
},
1114+
"consider_front_overhang": {
1115+
"type": "boolean",
1116+
"description": "Flag to consider vehicle front overhang in shift line generation logic.",
1117+
"default": true
1118+
},
1119+
"consider_rear_overhang": {
1120+
"type": "boolean",
1121+
"description": "Flag to consider vehicle rear overhang in shift line generation logic.",
1122+
"default": true
11531123
}
11541124
},
11551125
"required": [
@@ -1158,7 +1128,9 @@
11581128
"min_prepare_distance",
11591129
"min_slow_down_speed",
11601130
"buf_slow_down_speed",
1161-
"nominal_avoidance_speed"
1131+
"nominal_avoidance_speed",
1132+
"consider_front_overhang",
1133+
"consider_rear_overhang"
11621134
],
11631135
"additionalProperties": false
11641136
},

planning/behavior_path_avoidance_module/src/manager.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -59,9 +59,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
5959
parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle",
6060
config.lateral_hard_margin_for_parked_vehicle);
6161
updateParam<double>(parameters, ns + "longitudinal_margin", config.longitudinal_margin);
62-
updateParam<bool>(
63-
parameters, ns + "use_conservative_buffer_longitudinal",
64-
config.use_conservative_buffer_longitudinal);
6562
};
6663

6764
{
@@ -170,6 +167,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
170167
updateParam<double>(parameters, ns + "min_prepare_distance", p->min_prepare_distance);
171168
updateParam<double>(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed);
172169
updateParam<double>(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed);
170+
updateParam<bool>(parameters, ns + "consider_front_overhang", p->consider_front_overhang);
171+
updateParam<bool>(parameters, ns + "consider_rear_overhang", p->consider_rear_overhang);
173172
}
174173

175174
{

0 commit comments

Comments
 (0)