Skip to content

Commit

Permalink
refactor(avoidance): unify redundant parameters (#6798)
Browse files Browse the repository at this point in the history
* refactor(avoidance): unify redundant parameters

Signed-off-by: satoshi-ota <[email protected]>

* refactor(avoidance): remove unused parameters

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Apr 12, 2024
1 parent 8793584 commit 682a814
Show file tree
Hide file tree
Showing 6 changed files with 29 additions and 68 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
hard_margin_for_parked_vehicle: 0.7 # [m]
max_expand_ratio: 0.0 # [-] FOR DEVELOPER
envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER
use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
truck:
th_moving_speed: 1.0
th_moving_time: 2.0
Expand All @@ -39,7 +38,6 @@
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
use_conservative_buffer_longitudinal: true
bus:
th_moving_speed: 1.0
th_moving_time: 2.0
Expand All @@ -50,7 +48,6 @@
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
use_conservative_buffer_longitudinal: true
trailer:
th_moving_speed: 1.0
th_moving_time: 2.0
Expand All @@ -61,7 +58,6 @@
hard_margin_for_parked_vehicle: 0.7
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
use_conservative_buffer_longitudinal: true
unknown:
th_moving_speed: 0.28
th_moving_time: 1.0
Expand All @@ -72,7 +68,6 @@
hard_margin_for_parked_vehicle: -0.2
max_expand_ratio: 0.0
envelope_buffer_margin: 0.1
use_conservative_buffer_longitudinal: true
bicycle:
th_moving_speed: 0.28
th_moving_time: 1.0
Expand All @@ -83,7 +78,6 @@
hard_margin_for_parked_vehicle: 0.5
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
use_conservative_buffer_longitudinal: true
motorcycle:
th_moving_speed: 1.0
th_moving_time: 1.0
Expand All @@ -94,7 +88,6 @@
hard_margin_for_parked_vehicle: 0.3
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
use_conservative_buffer_longitudinal: true
pedestrian:
th_moving_speed: 0.28
th_moving_time: 1.0
Expand All @@ -105,7 +98,6 @@
hard_margin_for_parked_vehicle: 0.5
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
use_conservative_buffer_longitudinal: true
lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER
upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER

Expand Down Expand Up @@ -222,6 +214,8 @@
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER
nominal_avoidance_speed: 8.33 # [m/s] FOR DEVELOPER
consider_front_overhang: true # [-]
consider_rear_overhang: true # [-]
# return dead line
return_dead_line:
goal:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,6 @@ struct ObjectParameter
double lateral_hard_margin_for_parked_vehicle{1.0};

double longitudinal_margin{0.0};

bool use_conservative_buffer_longitudinal{true};
};

struct AvoidanceParameters
Expand Down Expand Up @@ -191,14 +189,6 @@ struct AvoidanceParameters
double time_threshold_for_ambiguous_vehicle{0.0};
double distance_threshold_for_ambiguous_vehicle{0.0};

// when complete avoidance motion, there is a distance margin with the object
// for longitudinal direction
double longitudinal_collision_margin_min_distance{0.0};

// when complete avoidance motion, there is a time margin with the object
// for longitudinal direction
double longitudinal_collision_margin_time{0.0};

// parameters for safety check area
bool enable_safety_check{false};
bool check_current_lane{false};
Expand All @@ -219,6 +209,9 @@ struct AvoidanceParameters
size_t hysteresis_factor_safe_count;
double hysteresis_factor_expand_rate{0.0};

bool consider_front_overhang{true};
bool consider_rear_overhang{true};

// maximum stop distance
double stop_max_distance{0.0};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,16 +148,19 @@ class AvoidanceHelper
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto & additional_buffer_longitudinal =
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
: 0.0;
return object_parameter.longitudinal_margin + additional_buffer_longitudinal;
if (!parameters_->consider_front_overhang) {
return object_parameter.longitudinal_margin;
}
return object_parameter.longitudinal_margin + data_->parameters.base_link2front;
}

double getRearConstantDistance(const ObjectData & object) const
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
if (!parameters_->consider_rear_overhang) {
return object_parameter.longitudinal_margin;
}
return object_parameter.longitudinal_margin + data_->parameters.base_link2rear + object.length;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
param.lateral_hard_margin_for_parked_vehicle =
getOrDeclareParameter<double>(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle");
param.longitudinal_margin = getOrDeclareParameter<double>(*node, ns + "longitudinal_margin");
param.use_conservative_buffer_longitudinal =
getOrDeclareParameter<bool>(*node, ns + "use_conservative_buffer_longitudinal");
return param;
};

Expand Down Expand Up @@ -270,6 +268,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
p.buf_slow_down_speed = getOrDeclareParameter<double>(*node, ns + "buf_slow_down_speed");
p.nominal_avoidance_speed =
getOrDeclareParameter<double>(*node, ns + "nominal_avoidance_speed");
p.consider_front_overhang = getOrDeclareParameter<bool>(*node, ns + "consider_front_overhang");
p.consider_rear_overhang = getOrDeclareParameter<bool>(*node, ns + "consider_rear_overhang");
}

// avoidance maneuver (return shift dead line)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,11 +104,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -171,11 +166,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -238,11 +228,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -305,11 +290,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -372,11 +352,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -439,11 +414,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -506,11 +476,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -573,11 +538,6 @@
"type": "number",
"description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.",
"default": 0.0
},
"use_conservative_buffer_longitudinal": {
"type": "boolean",
"description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.",
"default": "true"
}
},
"required": [
Expand Down Expand Up @@ -1150,6 +1110,16 @@
"type": "number",
"description": "Nominal avoidance speed.",
"default": 8.33
},
"consider_front_overhang": {
"type": "boolean",
"description": "Flag to consider vehicle front overhang in shift line generation logic.",
"default": true
},
"consider_rear_overhang": {
"type": "boolean",
"description": "Flag to consider vehicle rear overhang in shift line generation logic.",
"default": true
}
},
"required": [
Expand All @@ -1158,7 +1128,9 @@
"min_prepare_distance",
"min_slow_down_speed",
"buf_slow_down_speed",
"nominal_avoidance_speed"
"nominal_avoidance_speed",
"consider_front_overhang",
"consider_rear_overhang"
],
"additionalProperties": false
},
Expand Down
5 changes: 2 additions & 3 deletions planning/behavior_path_avoidance_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle",
config.lateral_hard_margin_for_parked_vehicle);
updateParam<double>(parameters, ns + "longitudinal_margin", config.longitudinal_margin);
updateParam<bool>(
parameters, ns + "use_conservative_buffer_longitudinal",
config.use_conservative_buffer_longitudinal);
};

{
Expand Down Expand Up @@ -170,6 +167,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
updateParam<double>(parameters, ns + "min_prepare_distance", p->min_prepare_distance);
updateParam<double>(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed);
updateParam<double>(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed);
updateParam<bool>(parameters, ns + "consider_front_overhang", p->consider_front_overhang);
updateParam<bool>(parameters, ns + "consider_rear_overhang", p->consider_rear_overhang);
}

{
Expand Down

0 comments on commit 682a814

Please sign in to comment.