Skip to content

Commit 8444898

Browse files
authored
feat(avoidance): improve avoidance stop & decel behavior (autowarefoundation#4141) (#651)
* feat(path_shifter): add utils * feat(avoidance): shorten avoidance stop distance * feat(avoidance): insert slow down speed * fix(avoidance): don't set stoppable=true for objects that ego doesn't have to avoid * refactor(avoidance): rename unreadable variable name * docs(avoidance): add new parameter description --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent e5e1d2d commit 8444898

File tree

11 files changed

+133
-54
lines changed

11 files changed

+133
-54
lines changed

planning/behavior_path_planner/config/avoidance/avoidance.param.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -145,6 +145,8 @@
145145
min_avoidance_distance: 10.0 # [m]
146146
min_nominal_avoidance_speed: 7.0 # [m/s]
147147
min_sharp_avoidance_speed: 1.0 # [m/s]
148+
min_slow_down_speed: 1.38 # [m/s]
149+
buf_slow_down_speed: 0.56 # [m/s]
148150

149151
# For yield maneuver
150152
yield:
@@ -154,6 +156,7 @@
154156
stop:
155157
min_distance: 10.0 # [m]
156158
max_distance: 20.0 # [m]
159+
stop_buffer: 1.0 # [m]
157160

158161
constraints:
159162
# vehicle slows down under longitudinal constraints

planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md

+11-8
Original file line numberDiff line numberDiff line change
@@ -658,14 +658,16 @@ namespace: `avoidance.avoidance.lateral.`
658658

659659
namespace: `avoidance.avoidance.longitudinal.`
660660

661-
| Name | Unit | Type | Description | Default value |
662-
| :----------------------------------- | :---- | :----- | :----------------------------------------------------------------------------------------------------- | :------------ |
663-
| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 |
664-
| longitudinal_collision_safety_buffer | [s] | double | Longitudinal collision buffer between target object and shift line. | 0.0 |
665-
| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 |
666-
| min_avoidance_distance | [m] | double | Minimum distance of avoidance path (i.e. this distance is needed even if its lateral jerk is very low) | 10.0 |
667-
| min_nominal_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a nominal situation (\*1). | 7.0 |
668-
| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 |
661+
| Name | Unit | Type | Description | Default value |
662+
| :----------------------------------- | :---- | :----- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------- |
663+
| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 |
664+
| longitudinal_collision_safety_buffer | [s] | double | Longitudinal collision buffer between target object and shift line. | 0.0 |
665+
| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 |
666+
| min_avoidance_distance | [m] | double | Minimum distance of avoidance path (i.e. this distance is needed even if its lateral jerk is very low) | 10.0 |
667+
| min_nominal_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a nominal situation (\*1). | 7.0 |
668+
| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 |
669+
| min_slow_down_speed | [m/s] | double | Minimum slow speed for avoidance prepare section. | 1.38 (5km/h) |
670+
| buf_slow_down_speed | [m/s] | double | Buffer for controller tracking error. Basically, vehicle always cannot follow velocity profile precisely. Therefore, the module inserts lower speed than target speed that satisfies conditions to avoid object within accel/jerk constraints so that the avoidance path always can be output even if the current speed is a little bit higher than target speed. | 0.57 (2.0km/h) |
669671

670672
### Yield maneuver parameters
671673

@@ -683,6 +685,7 @@ namespace: `avoidance.stop.`
683685
| :----------- | :--- | :----- | :---------------------------------------------------------------------------------------------------- | :------------ |
684686
| min_distance | [m] | double | Minimum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 10.0 |
685687
| max_distance | [m] | double | Maximum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 20.0 |
688+
| stop_buffer | [m] | double | Buffer distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 1.0 |
686689

687690
### Constraints parameters
688691

planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -199,6 +199,9 @@ struct AvoidanceParameters
199199
// maximum stop distance
200200
double stop_max_distance;
201201

202+
// stop buffer
203+
double stop_buffer;
204+
202205
// start avoidance after this time to avoid sudden path change
203206
double prepare_time;
204207

@@ -219,6 +222,12 @@ struct AvoidanceParameters
219222
// distance for avoidance. Need a sharp avoidance path to avoid the object.
220223
double min_sharp_avoidance_speed;
221224

225+
// minimum slow down speed
226+
double min_slow_down_speed;
227+
228+
// slow down speed buffer
229+
double buf_slow_down_speed;
230+
222231
// The margin is configured so that the generated avoidance trajectory does not come near to the
223232
// road shoulder.
224233
double road_shoulder_safety_margin{1.0};

planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp

+1-8
Original file line numberDiff line numberDiff line change
@@ -74,13 +74,6 @@ class AvoidanceHelper
7474
return std::max(getEgoSpeed(), parameters_->min_sharp_avoidance_speed);
7575
}
7676

77-
float getMaximumAvoidanceEgoSpeed() const
78-
{
79-
return parameters_->target_velocity_matrix.at(parameters_->col_size - 1);
80-
}
81-
82-
float getMinimumAvoidanceEgoSpeed() const { return parameters_->target_velocity_matrix.front(); }
83-
8477
double getNominalPrepareDistance() const
8578
{
8679
const auto & p = parameters_;
@@ -103,7 +96,7 @@ class AvoidanceHelper
10396
{
10497
const auto & p = parameters_;
10598
const auto distance_by_jerk = PathShifter::calcLongitudinalDistFromJerk(
106-
shift_length, p->nominal_lateral_jerk, getMinimumAvoidanceEgoSpeed());
99+
shift_length, p->max_lateral_jerk, p->min_sharp_avoidance_speed);
107100

108101
return std::max(p->min_avoidance_distance, distance_by_jerk);
109102
}

planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -136,6 +136,9 @@ class PathShifter
136136
// Utility Functions
137137
////////////////////////////////////////
138138

139+
static double calcFeasibleVelocityFromJerk(
140+
const double lateral, const double jerk, const double distance);
141+
139142
static double calcLongitudinalDistFromJerk(
140143
const double lateral, const double jerk, const double velocity);
141144

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -643,6 +643,8 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam()
643643
p.min_avoidance_distance = declare_parameter<double>(ns + "min_avoidance_distance");
644644
p.min_nominal_avoidance_speed = declare_parameter<double>(ns + "min_nominal_avoidance_speed");
645645
p.min_sharp_avoidance_speed = declare_parameter<double>(ns + "min_sharp_avoidance_speed");
646+
p.min_slow_down_speed = declare_parameter<double>(ns + "min_slow_down_speed");
647+
p.buf_slow_down_speed = declare_parameter<double>(ns + "buf_slow_down_speed");
646648
}
647649

648650
// yield
@@ -656,6 +658,7 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam()
656658
std::string ns = "avoidance.stop.";
657659
p.stop_min_distance = declare_parameter<double>(ns + "min_distance");
658660
p.stop_max_distance = declare_parameter<double>(ns + "max_distance");
661+
p.stop_buffer = declare_parameter<double>(ns + "stop_buffer");
659662
}
660663

661664
// constraints

planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -104,9 +104,11 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st
104104
marker.id = uuidToInt32(object.object.object_id);
105105
marker.pose = object.object.kinematics.initial_pose_with_covariance.pose;
106106
std::ostringstream string_stream;
107-
string_stream << std::fixed << std::setprecision(2);
107+
string_stream << std::fixed << std::setprecision(2) << std::boolalpha;
108108
string_stream << "ratio:" << object.shiftable_ratio << " [-]\n"
109-
<< "lateral: " << object.lateral << " [-]\n"
109+
<< "lateral:" << object.lateral << " [m]\n"
110+
<< "necessity:" << object.avoid_required << " [-]\n"
111+
<< "stoppable:" << object.is_stoppable << " [-]\n"
110112
<< "stop_factor:" << object.to_stop_factor_distance << " [m]\n"
111113
<< "move_time:" << object.move_time << " [s]\n"
112114
<< "stop_time:" << object.stop_time << " [s]\n";

planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp

+61-19
Original file line numberDiff line numberDiff line change
@@ -397,8 +397,8 @@ ObjectData AvoidanceModule::createObjectData(
397397
const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose;
398398
const auto object_closest_index = findNearestIndex(path_points, object_pose.position);
399399
const auto object_closest_pose = path_points.at(object_closest_index).point.pose;
400-
const auto t = utils::getHighestProbLabel(object.classification);
401-
const auto object_parameter = parameters_->object_parameters.at(t);
400+
const auto object_type = utils::getHighestProbLabel(object.classification);
401+
const auto object_parameter = parameters_->object_parameters.at(object_type);
402402

403403
ObjectData object_data{};
404404

@@ -640,8 +640,8 @@ void AvoidanceModule::fillDebugData(const AvoidancePlanningData & data, DebugDat
640640
}
641641

642642
const auto o_front = data.stop_target_object.get();
643-
const auto t = utils::getHighestProbLabel(o_front.object.classification);
644-
const auto object_parameter = parameters_->object_parameters.at(t);
643+
const auto object_type = utils::getHighestProbLabel(o_front.object.classification);
644+
const auto object_parameter = parameters_->object_parameters.at(object_type);
645645
const auto & base_link2front = planner_data_->parameters.base_link2front;
646646
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
647647

@@ -689,6 +689,8 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif
689689
return;
690690
}
691691

692+
insertPrepareVelocity(path);
693+
692694
switch (data.state) {
693695
case AvoidanceState::NOT_AVOID: {
694696
break;
@@ -700,7 +702,6 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif
700702
break;
701703
}
702704
case AvoidanceState::AVOID_PATH_NOT_READY: {
703-
insertPrepareVelocity(path);
704705
insertWaitPoint(parameters_->use_constraints_for_decel, path);
705706
break;
706707
}
@@ -931,8 +932,8 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects(
931932
const auto nominal_return_distance = helper_.getNominalAvoidanceDistance(return_shift);
932933

933934
// use each object param
934-
const auto t = utils::getHighestProbLabel(o.object.classification);
935-
const auto object_parameter = parameters_->object_parameters.at(t);
935+
const auto object_type = utils::getHighestProbLabel(o.object.classification);
936+
const auto object_parameter = parameters_->object_parameters.at(object_type);
936937

937938
/**
938939
* Is there enough distance from ego to object for avoidance?
@@ -3317,15 +3318,15 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const
33173318
// D4: o_front.longitudinal
33183319
// D5: base_link2front
33193320

3320-
const auto t = utils::getHighestProbLabel(object.object.classification);
3321-
const auto object_parameter = parameters_->object_parameters.at(t);
3321+
const auto object_type = utils::getHighestProbLabel(object.object.classification);
3322+
const auto object_parameter = parameters_->object_parameters.at(object_type);
33223323

33233324
const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor +
33243325
object_parameter.avoid_margin_lateral + 0.5 * vehicle_width;
33253326
const auto variable = helper_.getMinimumAvoidanceDistance(
33263327
helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin));
3327-
const auto constant =
3328-
p->min_prepare_distance + object_parameter.safety_buffer_longitudinal + base_link2front;
3328+
const auto constant = p->min_prepare_distance + object_parameter.safety_buffer_longitudinal +
3329+
base_link2front + p->stop_buffer;
33293330

33303331
return object.longitudinal -
33313332
std::clamp(variable + constant, p->stop_min_distance, p->stop_max_distance);
@@ -3436,23 +3437,64 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
34363437
{
34373438
const auto & data = avoidance_data_;
34383439

3440+
// do nothing if there is no avoidance target.
34393441
if (data.target_objects.empty()) {
34403442
return;
34413443
}
34423444

3443-
if (!!data.stop_target_object) {
3444-
if (data.stop_target_object.get().reason != AvoidanceDebugFactor::TOO_LARGE_JERK) {
3445-
return;
3446-
}
3445+
// insert slow down speed only when the avoidance maneuver is not initiated.
3446+
if (data.avoiding_now) {
3447+
return;
34473448
}
34483449

3449-
if (data.avoiding_now) {
3450+
// insert slow down speed only when no shift line is approved.
3451+
if (!path_shifter_.getShiftLines().empty()) {
34503452
return;
34513453
}
34523454

3453-
const auto decel_distance = helper_.getFeasibleDecelDistance(0.0);
3454-
utils::avoidance::insertDecelPoint(
3455-
getEgoPosition(), decel_distance, 0.0, shifted_path.path, slow_pose_);
3455+
const auto object = data.target_objects.front();
3456+
3457+
// calculate shift length for front object.
3458+
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
3459+
const auto object_type = utils::getHighestProbLabel(object.object.classification);
3460+
const auto object_parameter = parameters_->object_parameters.at(object_type);
3461+
const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor +
3462+
object_parameter.avoid_margin_lateral + 0.5 * vehicle_width;
3463+
const auto shift_length =
3464+
helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin);
3465+
3466+
// check slow down feasibility
3467+
const auto min_avoid_distance = helper_.getMinimumAvoidanceDistance(shift_length);
3468+
const auto distance_to_object = object.longitudinal;
3469+
const auto remaining_distance = distance_to_object - min_avoid_distance;
3470+
const auto decel_distance =
3471+
helper_.getFeasibleDecelDistance(parameters_->min_sharp_avoidance_speed);
3472+
if (remaining_distance < decel_distance) {
3473+
return;
3474+
}
3475+
3476+
// decide slow down lower limit.
3477+
const auto lower_speed = object.avoid_required ? 0.0 : parameters_->min_slow_down_speed;
3478+
3479+
// insert slow down speed.
3480+
const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points);
3481+
for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) {
3482+
const auto distance_from_ego = calcSignedArcLength(shifted_path.path.points, start_idx, i);
3483+
3484+
// slow down speed is inserted only in front of the object.
3485+
const auto shift_longitudinal_distance = distance_to_object - distance_from_ego;
3486+
if (shift_longitudinal_distance < min_avoid_distance) {
3487+
break;
3488+
}
3489+
3490+
// target speed with nominal jerk limits.
3491+
const double v_target = PathShifter::calcFeasibleVelocityFromJerk(
3492+
shift_length, parameters_->nominal_lateral_jerk, shift_longitudinal_distance);
3493+
const double v_original = shifted_path.path.points.at(i).point.longitudinal_velocity_mps;
3494+
const double v_insert = std::max(v_target - parameters_->buf_slow_down_speed, lower_speed);
3495+
3496+
shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_insert);
3497+
}
34563498
}
34573499

34583500
std::shared_ptr<AvoidanceDebugMsgArray> AvoidanceModule::get_debug_msg_array() const

planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -90,12 +90,15 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
9090
{
9191
const std::string ns = "avoidance.avoidance.longitudinal.";
9292
updateParam<double>(parameters, ns + "prepare_time", p->prepare_time);
93+
updateParam<double>(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed);
94+
updateParam<double>(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed);
9395
}
9496

9597
{
9698
const std::string ns = "avoidance.stop.";
9799
updateParam<double>(parameters, ns + "max_distance", p->stop_max_distance);
98100
updateParam<double>(parameters, ns + "min_distance", p->stop_min_distance);
101+
updateParam<double>(parameters, ns + "stop_buffer", p->stop_buffer);
99102
}
100103

101104
{

0 commit comments

Comments
 (0)