Skip to content

Commit c6b802f

Browse files
beyzanurkayabeyzapre-commit-ci[bot]
authored
fix(behavior_path_planner): if ego leaves the current lane turn the signal on (#4348)
* if ego leaves its lane due the avoidance, turn the signal on Signed-off-by: beyza <bnk@leodrive.ai> * add right_bound check Signed-off-by: beyza <bnk@leodrive.ai> * style(pre-commit): autofix --------- Signed-off-by: beyza <bnk@leodrive.ai> Co-authored-by: beyza <bnk@leodrive.ai> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 89404e6 commit c6b802f

File tree

1 file changed

+25
-2
lines changed

1 file changed

+25
-2
lines changed

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

+25-2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "behavior_path_planner/marker_utils/avoidance/debug.hpp"
1818
#include "behavior_path_planner/scene_module/scene_module_visitor.hpp"
1919
#include "behavior_path_planner/utils/avoidance/utils.hpp"
20+
#include "behavior_path_planner/utils/create_vehicle_footprint.hpp"
2021
#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp"
2122
#include "behavior_path_planner/utils/path_utils.hpp"
2223
#include "behavior_path_planner/utils/utils.hpp"
@@ -2543,9 +2544,31 @@ TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) con
25432544
turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
25442545
}
25452546
} else {
2546-
turn_signal_info.turn_signal.command = TurnIndicatorsCommand::DISABLE;
2547+
const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_);
2548+
const auto local_vehicle_footprint =
2549+
createVehicleFootprint(planner_data_->parameters.vehicle_info);
2550+
boost::geometry::model::ring<tier4_autoware_utils::Point2d> shifted_vehicle_footprint;
2551+
for (const auto & cl : current_lanes) {
2552+
// get left and right bounds of current lane
2553+
const auto lane_left_bound = cl.leftBound2d().basicLineString();
2554+
const auto lane_right_bound = cl.rightBound2d().basicLineString();
2555+
for (size_t i = start_idx; i < end_idx; ++i) {
2556+
// transform vehicle footprint onto path points
2557+
shifted_vehicle_footprint = transformVector(
2558+
local_vehicle_footprint,
2559+
tier4_autoware_utils::pose2transform(path.path.points.at(i).point.pose));
2560+
if (
2561+
boost::geometry::intersects(lane_left_bound, shifted_vehicle_footprint) ||
2562+
boost::geometry::intersects(lane_right_bound, shifted_vehicle_footprint)) {
2563+
if (segment_shift_length > 0.0) {
2564+
turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT;
2565+
} else {
2566+
turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
2567+
}
2568+
}
2569+
}
2570+
}
25472571
}
2548-
25492572
if (ego_front_to_shift_start > 0.0) {
25502573
turn_signal_info.desired_start_point = planner_data_->self_odometry->pose.pose;
25512574
} else {

0 commit comments

Comments
 (0)