@@ -392,6 +392,40 @@ TurnIndicatorsCommand TurnSignalDecider::resolve_turn_signal(
392
392
return intersection_signal_info.turn_signal ;
393
393
}
394
394
395
+ TurnSignalInfo TurnSignalDecider::overwrite_turn_signal (
396
+ const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
397
+ const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
398
+ const double nearest_dist_threshold, const double nearest_yaw_threshold) const
399
+ {
400
+ if (original_signal.turn_signal .command == TurnIndicatorsCommand::NO_COMMAND) {
401
+ return new_signal;
402
+ }
403
+
404
+ if (original_signal.turn_signal .command == TurnIndicatorsCommand::DISABLE) {
405
+ return new_signal;
406
+ }
407
+
408
+ const auto get_distance = [&](const Pose & input_point) {
409
+ const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints (
410
+ path.points , input_point, nearest_dist_threshold, nearest_yaw_threshold);
411
+ return motion_utils::calcSignedArcLength (
412
+ path.points , current_pose.position , current_seg_idx, input_point.position ,
413
+ nearest_seg_idx) -
414
+ base_link2front_;
415
+ };
416
+
417
+ const auto & original_desired_end_point = original_signal.desired_end_point ;
418
+ const auto & new_desired_start_point = new_signal.desired_start_point ;
419
+
420
+ const double dist_to_original_desired_end = get_distance (original_desired_end_point);
421
+ const double dist_to_new_desired_start = get_distance (new_desired_start_point);
422
+ if (dist_to_new_desired_start > dist_to_original_desired_end) {
423
+ return original_signal;
424
+ }
425
+
426
+ return new_signal;
427
+ }
428
+
395
429
TurnSignalInfo TurnSignalDecider::use_prior_turn_signal (
396
430
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
397
431
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
@@ -615,6 +649,8 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
615
649
const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted,
616
650
const bool override_ego_stopped_check, const bool is_pull_out) const
617
651
{
652
+ using tier4_autoware_utils::getPose;
653
+
618
654
const auto & p = parameters;
619
655
const auto & rh = route_handler;
620
656
const auto & ego_pose = self_odometry->pose .pose ;
@@ -667,16 +703,19 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
667
703
668
704
const auto relative_shift_length = end_shift_length - start_shift_length;
669
705
706
+ const auto p_path_start = getPose (path.path .points .front ());
707
+ const auto p_path_end = getPose (path.path .points .back ());
708
+
670
709
// If shift length is shorter than the threshold, it does not need to turn on blinkers
671
710
if (std::fabs (relative_shift_length) < p.turn_signal_shift_length_threshold ) {
672
- return std::make_pair (TurnSignalInfo{} , true );
711
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
673
712
}
674
713
675
714
// If the vehicle does not shift anymore, we turn off the blinker
676
715
if (
677
716
std::fabs (end_shift_length - current_shift_length) <
678
717
p.turn_signal_remaining_shift_length_threshold ) {
679
- return std::make_pair (TurnSignalInfo{} , true );
718
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
680
719
}
681
720
682
721
const auto get_command = [](const auto & shift_length) {
@@ -691,7 +730,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
691
730
p.vehicle_info .max_longitudinal_offset_m ;
692
731
693
732
if (signal_prepare_distance < ego_front_to_shift_start) {
694
- return std::make_pair (TurnSignalInfo{} , false );
733
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , false );
695
734
}
696
735
697
736
const auto blinker_start_pose = path.path .points .at (shift_line.start_idx ).point .pose ;
@@ -708,13 +747,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
708
747
turn_signal_info.turn_signal .command = get_command (relative_shift_length);
709
748
710
749
if (!p.turn_signal_on_swerving ) {
711
- return std::make_pair (turn_signal_info , false );
750
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , false );
712
751
}
713
752
714
753
lanelet::ConstLanelet lanelet;
715
754
const auto query_pose = (egos_lane_is_shifted) ? shift_line.end : shift_line.start ;
716
755
if (!rh->getClosestLaneletWithinRoute (query_pose, &lanelet)) {
717
- return std::make_pair (TurnSignalInfo{} , true );
756
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
718
757
}
719
758
720
759
const auto left_same_direction_lane = rh->getLeftLanelet (lanelet, true , true );
@@ -729,13 +768,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
729
768
!is_pull_out && !existShiftSideLane (
730
769
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
731
770
p.turn_signal_shift_length_threshold )) {
732
- return std::make_pair (TurnSignalInfo{} , true );
771
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
733
772
}
734
773
735
774
// Check if the ego will cross lane bounds.
736
775
// Note that pull out requires blinkers, even if the ego does not cross lane bounds
737
776
if (!is_pull_out && !straddleRoadBound (path, shift_line, current_lanelets, p.vehicle_info )) {
738
- return std::make_pair (TurnSignalInfo{} , true );
777
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
739
778
}
740
779
741
780
// If the ego has stopped and its close to completing its shift, turn off the blinkers
@@ -744,7 +783,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
744
783
if (isNearEndOfShift (
745
784
start_shift_length, end_shift_length, ego_pose.position , current_lanelets,
746
785
p.turn_signal_shift_length_threshold )) {
747
- return std::make_pair (TurnSignalInfo{} , true );
786
+ return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
748
787
}
749
788
}
750
789
0 commit comments