Skip to content

Commit bac9dd1

Browse files
committed
fix(avoidance): turn off blinker when the ego return original lane
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 8043ba5 commit bac9dd1

File tree

4 files changed

+89
-26
lines changed

4 files changed

+89
-26
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -404,6 +404,8 @@ class AvoidanceModule : public SceneModuleInterface
404404

405405
bool safe_{true};
406406

407+
std::optional<UUID> ignore_signal_{std::nullopt};
408+
407409
std::shared_ptr<AvoidanceHelper> helper_;
408410

409411
std::shared_ptr<AvoidanceParameters> parameters_;

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,7 @@ double calcDistanceToAvoidStartLine(
176176
const std::shared_ptr<const PlannerData> & planner_data,
177177
const std::shared_ptr<AvoidanceParameters> & parameters);
178178

179-
TurnSignalInfo calcTurnSignalInfo(
179+
std::pair<TurnSignalInfo, bool> calcTurnSignalInfo(
180180
const ShiftedPath & path, const ShiftLine & shift_line, const double current_shift_length,
181181
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data);
182182
} // namespace behavior_path_planner::utils::avoidance

planning/behavior_path_avoidance_module/src/scene.cpp

+16-1
Original file line numberDiff line numberDiff line change
@@ -918,19 +918,34 @@ BehaviorModuleOutput AvoidanceModule::plan()
918918

919919
BehaviorModuleOutput output;
920920

921+
const auto is_ignore_signal = [this](const UUID & uuid) {
922+
if (!ignore_signal_.has_value()) {
923+
return false;
924+
}
925+
926+
return ignore_signal_.value() == uuid;
927+
};
928+
929+
const auto update_ignore_signal = [this](const UUID & uuid, const bool is_ignore) {
930+
ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt;
931+
};
932+
921933
// turn signal info
922934
if (path_shifter_.getShiftLines().empty()) {
923935
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
936+
} else if (is_ignore_signal(path_shifter_.getShiftLines().front().id)) {
937+
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
924938
} else {
925939
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
926-
const auto new_signal = utils::avoidance::calcTurnSignalInfo(
940+
const auto [new_signal, is_ignore] = utils::avoidance::calcTurnSignalInfo(
927941
linear_shift_path, path_shifter_.getShiftLines().front(), helper_->getEgoShift(), avoid_data_,
928942
planner_data_);
929943
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points);
930944
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
931945
spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
932946
planner_data_->parameters.ego_nearest_dist_threshold,
933947
planner_data_->parameters.ego_nearest_yaw_threshold);
948+
update_ignore_signal(path_shifter_.getShiftLines().front().id, is_ignore);
934949
}
935950

936951
// sparse resampling for computational cost

planning/behavior_path_avoidance_module/src/utils.cpp

+70-24
Original file line numberDiff line numberDiff line change
@@ -250,16 +250,37 @@ void pushUniqueVector(T & base_vector, const T & additional_vector)
250250
base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end());
251251
}
252252

253+
bool isAvoidShift(const double start_shift_length, const double end_shift_length)
254+
{
255+
constexpr double THRESHOLD = 0.1;
256+
return std::abs(start_shift_length) < THRESHOLD && std::abs(end_shift_length) > THRESHOLD;
257+
}
258+
259+
bool isReturnShift(const double start_shift_length, const double end_shift_length)
260+
{
261+
constexpr double THRESHOLD = 0.1;
262+
return std::abs(start_shift_length) > THRESHOLD && std::abs(end_shift_length) < THRESHOLD;
263+
}
264+
265+
bool isLeftMiddleShift(const double start_shift_length, const double end_shift_length)
266+
{
267+
constexpr double THRESHOLD = 0.1;
268+
return start_shift_length > THRESHOLD && end_shift_length > THRESHOLD;
269+
}
270+
271+
bool isRightMiddleShift(const double start_shift_length, const double end_shift_length)
272+
{
273+
constexpr double THRESHOLD = 0.1;
274+
return start_shift_length < THRESHOLD && end_shift_length < THRESHOLD;
275+
}
276+
253277
bool existShiftSideLane(
254278
const double start_shift_length, const double end_shift_length, const bool no_left_lanes,
255279
const bool no_right_lanes)
256280
{
257-
constexpr double THRESHOLD = 0.1;
258281
const auto relative_shift_length = end_shift_length - start_shift_length;
259282

260-
const auto avoid_shift =
261-
std::abs(start_shift_length) < THRESHOLD && std::abs(end_shift_length) > THRESHOLD;
262-
if (avoid_shift) {
283+
if (isAvoidShift(start_shift_length, end_shift_length)) {
263284
// Left avoid. But there is no adjacent lane. No need blinker.
264285
if (relative_shift_length > 0.0 && no_left_lanes) {
265286
return false;
@@ -271,9 +292,7 @@ bool existShiftSideLane(
271292
}
272293
}
273294

274-
const auto return_shift =
275-
std::abs(start_shift_length) > THRESHOLD && std::abs(end_shift_length) < THRESHOLD;
276-
if (return_shift) {
295+
if (isReturnShift(start_shift_length, end_shift_length)) {
277296
// Right return. But there is no adjacent lane. No need blinker.
278297
if (relative_shift_length > 0.0 && no_right_lanes) {
279298
return false;
@@ -285,8 +304,7 @@ bool existShiftSideLane(
285304
}
286305
}
287306

288-
const auto left_middle_shift = start_shift_length > THRESHOLD && end_shift_length > THRESHOLD;
289-
if (left_middle_shift) {
307+
if (isLeftMiddleShift(start_shift_length, end_shift_length)) {
290308
// Left avoid. But there is no adjacent lane. No need blinker.
291309
if (relative_shift_length > 0.0 && no_left_lanes) {
292310
return false;
@@ -298,8 +316,7 @@ bool existShiftSideLane(
298316
}
299317
}
300318

301-
const auto right_middle_shift = start_shift_length < THRESHOLD && end_shift_length < THRESHOLD;
302-
if (right_middle_shift) {
319+
if (isRightMiddleShift(start_shift_length, end_shift_length)) {
303320
// Right avoid. But there is no adjacent lane. No need blinker.
304321
if (relative_shift_length < 0.0 && no_right_lanes) {
305322
return false;
@@ -314,6 +331,27 @@ bool existShiftSideLane(
314331
return true;
315332
}
316333

334+
bool isNearEndOfShift(
335+
const double start_shift_length, const double end_shift_length, const Point & ego_pos,
336+
const lanelet::ConstLanelets & original_lanes)
337+
{
338+
using boost::geometry::within;
339+
using lanelet::utils::to2D;
340+
using lanelet::utils::conversion::toLaneletPoint;
341+
342+
if (!isReturnShift(start_shift_length, end_shift_length)) {
343+
return false;
344+
}
345+
346+
for (const auto & lane : original_lanes) {
347+
if (within(to2D(toLaneletPoint(ego_pos)), lane.polygon2d().basicPolygon())) {
348+
return true;
349+
}
350+
}
351+
352+
return false;
353+
}
354+
317355
bool straddleRoadBound(
318356
const ShiftedPath & path, const ShiftLine & shift_line, const lanelet::ConstLanelets & lanes,
319357
const vehicle_info_util::VehicleInfo & vehicle_info)
@@ -2323,7 +2361,7 @@ double calcDistanceToReturnDeadLine(
23232361
return distance_to_return_dead_line;
23242362
}
23252363

2326-
TurnSignalInfo calcTurnSignalInfo(
2364+
std::pair<TurnSignalInfo, bool> calcTurnSignalInfo(
23272365
const ShiftedPath & path, const ShiftLine & shift_line, const double current_shift_length,
23282366
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data)
23292367
{
@@ -2335,22 +2373,22 @@ TurnSignalInfo calcTurnSignalInfo(
23352373

23362374
if (shift_line.start_idx + 1 > path.shift_length.size()) {
23372375
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
2338-
return {};
2376+
return std::make_pair(TurnSignalInfo{}, true);
23392377
}
23402378

23412379
if (shift_line.start_idx + 1 > path.path.points.size()) {
23422380
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
2343-
return {};
2381+
return std::make_pair(TurnSignalInfo{}, true);
23442382
}
23452383

23462384
if (shift_line.end_idx + 1 > path.shift_length.size()) {
23472385
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
2348-
return {};
2386+
return std::make_pair(TurnSignalInfo{}, true);
23492387
}
23502388

23512389
if (shift_line.end_idx + 1 > path.path.points.size()) {
23522390
RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency.");
2353-
return {};
2391+
return std::make_pair(TurnSignalInfo{}, true);
23542392
}
23552393

23562394
const auto start_shift_length = path.shift_length.at(shift_line.start_idx);
@@ -2359,12 +2397,12 @@ TurnSignalInfo calcTurnSignalInfo(
23592397

23602398
// If shift length is shorter than the threshold, it does not need to turn on blinkers
23612399
if (std::fabs(relative_shift_length) < p.turn_signal_shift_length_threshold) {
2362-
return {};
2400+
return std::make_pair(TurnSignalInfo{}, true);
23632401
}
23642402

23652403
// If the vehicle does not shift anymore, we turn off the blinker
23662404
if (std::fabs(path.shift_length.at(shift_line.end_idx) - current_shift_length) < THRESHOLD) {
2367-
return {};
2405+
return std::make_pair(TurnSignalInfo{}, true);
23682406
}
23692407

23702408
const auto get_command = [](const auto & shift_length) {
@@ -2379,7 +2417,7 @@ TurnSignalInfo calcTurnSignalInfo(
23792417
p.vehicle_info.max_longitudinal_offset_m;
23802418

23812419
if (signal_prepare_distance < ego_front_to_shift_start) {
2382-
return {};
2420+
return std::make_pair(TurnSignalInfo{}, false);
23832421
}
23842422

23852423
const auto blinker_start_pose = path.path.points.at(shift_line.start_idx).point.pose;
@@ -2396,12 +2434,12 @@ TurnSignalInfo calcTurnSignalInfo(
23962434
turn_signal_info.turn_signal.command = get_command(relative_shift_length);
23972435

23982436
if (!p.turn_signal_on_swerving) {
2399-
return turn_signal_info;
2437+
return std::make_pair(turn_signal_info, false);
24002438
}
24012439

24022440
lanelet::ConstLanelet lanelet;
24032441
if (!rh->getClosestLaneletWithinRoute(shift_line.end, &lanelet)) {
2404-
return {};
2442+
return std::make_pair(TurnSignalInfo{}, true);
24052443
}
24062444

24072445
const auto left_same_direction_lane = rh->getLeftLanelet(lanelet, true, true);
@@ -2413,13 +2451,21 @@ TurnSignalInfo calcTurnSignalInfo(
24132451
right_same_direction_lane.has_value() || !right_opposite_lanes.empty();
24142452

24152453
if (!existShiftSideLane(start_shift_length, end_shift_length, !has_left_lane, !has_right_lane)) {
2416-
return {};
2454+
return std::make_pair(TurnSignalInfo{}, true);
24172455
}
24182456

24192457
if (!straddleRoadBound(path, shift_line, data.current_lanelets, p.vehicle_info)) {
2420-
return {};
2458+
return std::make_pair(TurnSignalInfo{}, true);
2459+
}
2460+
2461+
constexpr double STOPPED_THRESHOLD = 0.1; // [m/s]
2462+
if (ego_speed < STOPPED_THRESHOLD) {
2463+
if (isNearEndOfShift(
2464+
start_shift_length, end_shift_length, ego_pose.position, data.current_lanelets)) {
2465+
return std::make_pair(TurnSignalInfo{}, true);
2466+
}
24212467
}
24222468

2423-
return turn_signal_info;
2469+
return std::make_pair(turn_signal_info, false);
24242470
}
24252471
} // namespace behavior_path_planner::utils::avoidance

0 commit comments

Comments
 (0)