Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(avoidance): cherry pick PRs #1280

Merged
merged 9 commits into from
May 2, 2024
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ Planning:
behavior_path_planner_avoidance:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils

behavior_path_planner_goal_planner:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
Expand Down
171 changes: 1 addition & 170 deletions planning/behavior_path_avoidance_module/README.md

Large diffs are not rendered by default.

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 @@ -140,6 +132,10 @@
th_shiftable_ratio: 0.8 # [-]
min_road_shoulder_width: 0.5 # [m] FOR DEVELOPER

# for merging/deviating vehicle
merging_vehicle:
th_overhang_distance: 0.0 # [m]

# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
avoidance_for_ambiguous_vehicle:
enable: true # [-]
Expand Down Expand Up @@ -222,6 +218,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 Expand Up @@ -296,4 +294,3 @@
# for debug
debug:
marker: false
console: false
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,13 +189,8 @@ 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};
// for merging/deviating vehicle
double th_overhang_distance{0.0};

// parameters for safety check area
bool enable_safety_check{false};
Expand All @@ -219,6 +212,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 Expand Up @@ -329,7 +325,6 @@ struct AvoidanceParameters

// debug
bool publish_debug_marker = false;
bool print_debug_info = false;
};

struct ObjectData // avoidance target
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 @@ -133,6 +131,11 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
getOrDeclareParameter<double>(*node, ns + "min_road_shoulder_width");
}

{
const std::string ns = "avoidance.target_filtering.merging_vehicle.";
p.th_overhang_distance = getOrDeclareParameter<double>(*node, ns + "th_overhang_distance");
}

{
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter<bool>(*node, ns + "enable");
Expand Down Expand Up @@ -270,6 +273,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 Expand Up @@ -379,7 +384,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
{
const std::string ns = "avoidance.debug.";
p.publish_debug_marker = getOrDeclareParameter<bool>(*node, ns + "marker");
p.print_debug_info = getOrDeclareParameter<bool>(*node, ns + "console");
}

return p;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -424,9 +424,6 @@ class AvoidanceModule : public SceneModuleInterface
// TODO(Satoshi OTA) create detected object manager.
ObjectDataArray registered_objects_;

// TODO(Satoshi OTA) remove mutable.
mutable ObjectDataArray detected_objects_;

// TODO(Satoshi OTA) remove this variable.
mutable ObjectDataArray ego_stopped_objects_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,9 @@ using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPoly
using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped;
using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon;

static constexpr const char * logger_namespace =
"planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils";

bool isOnRight(const ObjectData & obj);

double calcShiftLength(
Expand Down Expand Up @@ -112,8 +115,6 @@ void fillObjectStoppableJudge(
ObjectData & object_data, const ObjectDataArray & registered_objects,
const double feasible_stop_distance, const std::shared_ptr<AvoidanceParameters> & parameters);

void fillInitialPose(ObjectData & object_data, ObjectDataArray & detected_objects);

void updateRegisteredObject(
ObjectDataArray & registered_objects, const ObjectDataArray & now_objects,
const std::shared_ptr<AvoidanceParameters> & parameters);
Expand Down
Loading
Loading