|
17 | 17 | #include "behavior_path_planner/marker_utils/avoidance/debug.hpp"
|
18 | 18 | #include "behavior_path_planner/scene_module/scene_module_visitor.hpp"
|
19 | 19 | #include "behavior_path_planner/utils/avoidance/utils.hpp"
|
| 20 | +#include "behavior_path_planner/utils/create_vehicle_footprint.hpp" |
20 | 21 | #include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp"
|
21 | 22 | #include "behavior_path_planner/utils/path_utils.hpp"
|
22 | 23 | #include "behavior_path_planner/utils/utils.hpp"
|
@@ -2543,9 +2544,31 @@ TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) con
|
2543 | 2544 | turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
|
2544 | 2545 | }
|
2545 | 2546 | } 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 | + } |
2547 | 2571 | }
|
2548 |
| - |
2549 | 2572 | if (ego_front_to_shift_start > 0.0) {
|
2550 | 2573 | turn_signal_info.desired_start_point = planner_data_->self_odometry->pose.pose;
|
2551 | 2574 | } else {
|
|
0 commit comments