Skip to content

Commit aa6be89

Browse files
authoredApr 10, 2024
Merge pull request #1242 from tier4/hotfix/v0.26.1/cherry-pick-avoidance-pr
fix(avoidance): cherry pick avoidance hotfix PRs
2 parents 4f814c2 + 1a6f1d8 commit aa6be89

File tree

9 files changed

+267
-49
lines changed

9 files changed

+267
-49
lines changed
 

‎planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -287,7 +287,8 @@
287287
nominal_jerk: 0.5 # [m/sss]
288288
max_deceleration: -1.5 # [m/ss]
289289
max_jerk: 1.0 # [m/sss]
290-
max_acceleration: 1.0 # [m/ss]
290+
max_acceleration: 0.5 # [m/ss]
291+
min_velocity_to_limit_max_acceleration: 2.78 # [m/ss]
291292

292293
shift_line_pipeline:
293294
trim:

‎planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -143,6 +143,9 @@ struct AvoidanceParameters
143143
// To prevent large acceleration while avoidance.
144144
double max_acceleration{0.0};
145145

146+
// To prevent large acceleration while avoidance.
147+
double min_velocity_to_limit_max_acceleration{0.0};
148+
146149
// upper distance for envelope polygon expansion.
147150
double upper_distance_for_polygon_expansion{0.0};
148151

‎planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+75
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <algorithm>
2525
#include <limits>
2626
#include <memory>
27+
#include <utility>
2728
#include <vector>
2829

2930
namespace behavior_path_planner::helper::avoidance
@@ -32,7 +33,10 @@ namespace behavior_path_planner::helper::avoidance
3233
using behavior_path_planner::PathShifter;
3334
using behavior_path_planner::PlannerData;
3435
using motion_utils::calcDecelDistWithJerkAndAccConstraints;
36+
using motion_utils::calcLongitudinalOffsetPose;
37+
using motion_utils::calcSignedArcLength;
3538
using motion_utils::findNearestIndex;
39+
using tier4_autoware_utils::getPose;
3640

3741
class AvoidanceHelper
3842
{
@@ -61,6 +65,11 @@ class AvoidanceHelper
6165

6266
geometry_msgs::msg::Pose getEgoPose() const { return data_->self_odometry->pose.pose; }
6367

68+
geometry_msgs::msg::Point getEgoPosition() const
69+
{
70+
return data_->self_odometry->pose.pose.position;
71+
}
72+
6473
static size_t getConstraintsMapIndex(const double velocity, const std::vector<double> & values)
6574
{
6675
const auto itr = std::find_if(
@@ -262,6 +271,20 @@ class AvoidanceHelper
262271
return *itr;
263272
}
264273

274+
std::pair<double, double> getDistanceToAccelEndPoint(const PathWithLaneId & path)
275+
{
276+
updateAccelEndPoint(path);
277+
278+
if (!max_v_point_.has_value()) {
279+
return std::make_pair(0.0, std::numeric_limits<double>::max());
280+
}
281+
282+
const auto start_idx = data_->findEgoIndex(path.points);
283+
const auto distance =
284+
calcSignedArcLength(path.points, start_idx, max_v_point_.value().first.position);
285+
return std::make_pair(distance, max_v_point_.value().second);
286+
}
287+
265288
double getFeasibleDecelDistance(
266289
const double target_velocity, const bool use_hard_constraints = true) const
267290
{
@@ -367,6 +390,56 @@ class AvoidanceHelper
367390
return true;
368391
}
369392

393+
void updateAccelEndPoint(const PathWithLaneId & path)
394+
{
395+
const auto & p = parameters_;
396+
const auto & a_now = data_->self_acceleration->accel.accel.linear.x;
397+
if (a_now < 0.0) {
398+
max_v_point_ = std::nullopt;
399+
return;
400+
}
401+
402+
if (getEgoSpeed() < p->min_velocity_to_limit_max_acceleration) {
403+
max_v_point_ = std::nullopt;
404+
return;
405+
}
406+
407+
if (max_v_point_.has_value()) {
408+
return;
409+
}
410+
411+
const auto v0 = getEgoSpeed() + p->buf_slow_down_speed;
412+
413+
const auto t_neg_jerk = std::max(0.0, a_now - p->max_acceleration) / p->max_jerk;
414+
const auto v_neg_jerk = v0 + a_now * t_neg_jerk + std::pow(t_neg_jerk, 2.0) / 2.0;
415+
const auto x_neg_jerk = v0 * t_neg_jerk + a_now * std::pow(t_neg_jerk, 2.0) / 2.0 +
416+
p->max_jerk * std::pow(t_neg_jerk, 3.0) / 6.0;
417+
418+
const auto & v_max = data_->parameters.max_vel;
419+
if (v_max < v_neg_jerk) {
420+
max_v_point_ = std::nullopt;
421+
return;
422+
}
423+
424+
const auto t_max_accel = (v_max - v_neg_jerk) / p->max_acceleration;
425+
const auto x_max_accel =
426+
v_neg_jerk * t_max_accel + p->max_acceleration * std::pow(t_max_accel, 2.0) / 2.0;
427+
428+
const auto point =
429+
calcLongitudinalOffsetPose(path.points, getEgoPosition(), x_neg_jerk + x_max_accel);
430+
if (point.has_value()) {
431+
max_v_point_ = std::make_pair(point.value(), v_max);
432+
return;
433+
}
434+
435+
const auto x_end = calcSignedArcLength(path.points, getEgoPosition(), path.points.size() - 1);
436+
const auto t_end =
437+
(std::sqrt(v0 * v0 + 2.0 * p->max_acceleration * x_end) - v0) / p->max_acceleration;
438+
const auto v_end = v0 + p->max_acceleration * t_end;
439+
440+
max_v_point_ = std::make_pair(getPose(path.points.back()), v_end);
441+
}
442+
370443
void reset()
371444
{
372445
prev_reference_path_ = PathWithLaneId();
@@ -417,6 +490,8 @@ class AvoidanceHelper
417490
ShiftedPath prev_linear_shift_path_;
418491

419492
lanelet::ConstLanelets prev_driving_lanes_;
493+
494+
std::optional<std::pair<Pose, double>> max_v_point_;
420495
};
421496
} // namespace behavior_path_planner::helper::avoidance
422497

‎planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -313,6 +313,10 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
313313
p.use_shorten_margin_immediately =
314314
getOrDeclareParameter<bool>(*node, ns + "use_shorten_margin_immediately");
315315

316+
if (p.policy_approval != "per_shift_line" && p.policy_approval != "per_avoidance_maneuver") {
317+
throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'.");
318+
}
319+
316320
if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") {
317321
throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'.");
318322
}
@@ -330,6 +334,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
330334
p.max_deceleration = getOrDeclareParameter<double>(*node, ns + "max_deceleration");
331335
p.max_jerk = getOrDeclareParameter<double>(*node, ns + "max_jerk");
332336
p.max_acceleration = getOrDeclareParameter<double>(*node, ns + "max_acceleration");
337+
p.min_velocity_to_limit_max_acceleration =
338+
getOrDeclareParameter<double>(*node, ns + "min_velocity_to_limit_max_acceleration");
333339
}
334340

335341
// constraints (lateral)

‎planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -233,6 +233,12 @@ class AvoidanceModule : public SceneModuleInterface
233233
*/
234234
void insertPrepareVelocity(ShiftedPath & shifted_path) const;
235235

236+
/**
237+
* @brief insert max velocity in output path to limit acceleration.
238+
* @param target path.
239+
*/
240+
void insertAvoidanceVelocity(ShiftedPath & shifted_path) const;
241+
236242
/**
237243
* @brief calculate stop distance based on object's overhang.
238244
* @param stop distance.

‎planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -85,10 +85,6 @@ lanelet::ConstLanelets getAdjacentLane(
8585
const std::shared_ptr<const PlannerData> & planner_data,
8686
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift);
8787

88-
lanelet::ConstLanelets getTargetLanelets(
89-
const std::shared_ptr<const PlannerData> & planner_data, lanelet::ConstLanelets & route_lanelets,
90-
const double left_offset, const double right_offset);
91-
9288
lanelet::ConstLanelets getCurrentLanesFromPath(
9389
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data);
9490

‎planning/behavior_path_avoidance_module/src/manager.cpp

+111
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,76 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
9191
p->upper_distance_for_polygon_expansion);
9292
}
9393

94+
{
95+
const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) {
96+
if (p->object_parameters.count(object_type) == 0) {
97+
return;
98+
}
99+
updateParam<bool>(parameters, ns, p->object_parameters.at(object_type).is_avoidance_target);
100+
};
101+
102+
const std::string ns = "avoidance.target_filtering.";
103+
set_target_flag(ObjectClassification::CAR, ns + "target_type.car");
104+
set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck");
105+
set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer");
106+
set_target_flag(ObjectClassification::BUS, ns + "target_type.bus");
107+
set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian");
108+
set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle");
109+
set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle");
110+
set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown");
111+
112+
updateParam<double>(
113+
parameters, ns + "object_check_goal_distance", p->object_check_goal_distance);
114+
updateParam<double>(
115+
parameters, ns + "object_check_return_pose_distance", p->object_check_return_pose_distance);
116+
updateParam<double>(
117+
parameters, ns + "threshold_distance_object_is_on_center",
118+
p->threshold_distance_object_is_on_center);
119+
updateParam<double>(
120+
parameters, ns + "object_check_shiftable_ratio", p->object_check_shiftable_ratio);
121+
updateParam<double>(
122+
parameters, ns + "object_check_min_road_shoulder_width",
123+
p->object_check_min_road_shoulder_width);
124+
updateParam<double>(
125+
parameters, ns + "object_last_seen_threshold", p->object_last_seen_threshold);
126+
}
127+
128+
{
129+
const std::string ns = "avoidance.target_filtering.detection_area.";
130+
updateParam<bool>(parameters, ns + "static", p->use_static_detection_area);
131+
updateParam<double>(
132+
parameters, ns + "min_forward_distance", p->object_check_min_forward_distance);
133+
updateParam<double>(
134+
parameters, ns + "max_forward_distance", p->object_check_max_forward_distance);
135+
updateParam<double>(parameters, ns + "backward_distance", p->object_check_backward_distance);
136+
}
137+
138+
{
139+
const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle.";
140+
updateParam<bool>(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle);
141+
updateParam<double>(
142+
parameters, ns + "closest_distance_to_wait_and_see",
143+
p->closest_distance_to_wait_and_see_for_ambiguous_vehicle);
144+
updateParam<double>(
145+
parameters, ns + "condition.time_threshold", p->time_threshold_for_ambiguous_vehicle);
146+
updateParam<double>(
147+
parameters, ns + "condition.distance_threshold", p->distance_threshold_for_ambiguous_vehicle);
148+
updateParam<double>(
149+
parameters, ns + "ignore_area.traffic_light.front_distance",
150+
p->object_ignore_section_traffic_light_in_front_distance);
151+
updateParam<double>(
152+
parameters, ns + "ignore_area.crosswalk.front_distance",
153+
p->object_ignore_section_crosswalk_in_front_distance);
154+
updateParam<double>(
155+
parameters, ns + "ignore_area.crosswalk.behind_distance",
156+
p->object_ignore_section_crosswalk_behind_distance);
157+
}
158+
159+
{
160+
const std::string ns = "avoidance.target_filtering.intersection.";
161+
updateParam<double>(parameters, ns + "yaw_deviation", p->object_check_yaw_deviation);
162+
}
163+
94164
{
95165
const std::string ns = "avoidance.avoidance.lateral.";
96166
updateParam<double>(
@@ -107,6 +177,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
107177
const std::string ns = "avoidance.avoidance.longitudinal.";
108178
updateParam<double>(parameters, ns + "min_prepare_time", p->min_prepare_time);
109179
updateParam<double>(parameters, ns + "max_prepare_time", p->max_prepare_time);
180+
updateParam<double>(parameters, ns + "min_prepare_distance", p->min_prepare_distance);
110181
updateParam<double>(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed);
111182
updateParam<double>(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed);
112183
}
@@ -117,6 +188,33 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
117188
updateParam<double>(parameters, ns + "stop_buffer", p->stop_buffer);
118189
}
119190

191+
{
192+
const std::string ns = "avoidance.policy.";
193+
updateParam<std::string>(parameters, ns + "make_approval_request", p->policy_approval);
194+
updateParam<std::string>(parameters, ns + "deceleration", p->policy_deceleration);
195+
updateParam<std::string>(parameters, ns + "lateral_margin", p->policy_lateral_margin);
196+
updateParam<bool>(
197+
parameters, ns + "use_shorten_margin_immediately", p->use_shorten_margin_immediately);
198+
199+
if (p->policy_approval != "per_shift_line" && p->policy_approval != "per_avoidance_maneuver") {
200+
RCLCPP_ERROR(
201+
rclcpp::get_logger(__func__),
202+
"invalid policy. please select 'per_shift_line' or 'per_avoidance_maneuver'.");
203+
}
204+
205+
if (p->policy_deceleration != "best_effort" && p->policy_deceleration != "reliable") {
206+
RCLCPP_ERROR(
207+
rclcpp::get_logger(__func__),
208+
"invalid deceleration policy. Please select 'best_effort' or 'reliable'.");
209+
}
210+
211+
if (p->policy_lateral_margin != "best_effort" && p->policy_lateral_margin != "reliable") {
212+
RCLCPP_ERROR(
213+
rclcpp::get_logger(__func__),
214+
"invalid lateral margin policy. Please select 'best_effort' or 'reliable'.");
215+
}
216+
}
217+
120218
{
121219
const std::string ns = "avoidance.constrains.lateral.";
122220

@@ -146,6 +244,19 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
146244
}
147245
}
148246

247+
{
248+
const std::string ns = "avoidance.constraints.longitudinal.";
249+
250+
updateParam<double>(parameters, ns + "nominal_deceleration", p->nominal_deceleration);
251+
updateParam<double>(parameters, ns + "nominal_jerk", p->nominal_jerk);
252+
updateParam<double>(parameters, ns + "max_deceleration", p->max_deceleration);
253+
updateParam<double>(parameters, ns + "max_jerk", p->max_jerk);
254+
updateParam<double>(parameters, ns + "max_acceleration", p->max_acceleration);
255+
updateParam<double>(
256+
parameters, ns + "min_velocity_to_limit_max_acceleration",
257+
p->min_velocity_to_limit_max_acceleration);
258+
}
259+
149260
{
150261
const std::string ns = "avoidance.shift_line_pipeline.";
151262
updateParam<double>(

0 commit comments

Comments
 (0)