@@ -399,40 +399,6 @@ TurnIndicatorsCommand TurnSignalDecider::resolve_turn_signal(
399
399
return intersection_signal_info.turn_signal ;
400
400
}
401
401
402
- TurnSignalInfo TurnSignalDecider::overwrite_turn_signal (
403
- const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
404
- const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
405
- const double nearest_dist_threshold, const double nearest_yaw_threshold) const
406
- {
407
- if (original_signal.turn_signal .command == TurnIndicatorsCommand::NO_COMMAND) {
408
- return new_signal;
409
- }
410
-
411
- if (original_signal.turn_signal .command == TurnIndicatorsCommand::DISABLE) {
412
- return new_signal;
413
- }
414
-
415
- const auto get_distance = [&](const Pose & input_point) {
416
- const size_t nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints (
417
- path.points , input_point, nearest_dist_threshold, nearest_yaw_threshold);
418
- return motion_utils::calcSignedArcLength (
419
- path.points , current_pose.position , current_seg_idx, input_point.position ,
420
- nearest_seg_idx) -
421
- base_link2front_;
422
- };
423
-
424
- const auto & original_desired_end_point = original_signal.desired_end_point ;
425
- const auto & new_desired_start_point = new_signal.desired_start_point ;
426
-
427
- const double dist_to_original_desired_end = get_distance (original_desired_end_point);
428
- const double dist_to_new_desired_start = get_distance (new_desired_start_point);
429
- if (dist_to_new_desired_start > dist_to_original_desired_end) {
430
- return original_signal;
431
- }
432
-
433
- return new_signal;
434
- }
435
-
436
402
TurnSignalInfo TurnSignalDecider::use_prior_turn_signal (
437
403
const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx,
438
404
const TurnSignalInfo & original_signal, const TurnSignalInfo & new_signal,
@@ -656,8 +622,6 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
656
622
const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted,
657
623
const bool override_ego_stopped_check, const bool is_pull_out) const
658
624
{
659
- using tier4_autoware_utils::getPose;
660
-
661
625
const auto & p = parameters;
662
626
const auto & rh = route_handler;
663
627
const auto & ego_pose = self_odometry->pose .pose ;
@@ -710,19 +674,16 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
710
674
711
675
const auto relative_shift_length = end_shift_length - start_shift_length;
712
676
713
- const auto p_path_start = getPose (path.path .points .front ());
714
- const auto p_path_end = getPose (path.path .points .back ());
715
-
716
677
// If shift length is shorter than the threshold, it does not need to turn on blinkers
717
678
if (std::fabs (relative_shift_length) < p.turn_signal_shift_length_threshold ) {
718
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
679
+ return std::make_pair (TurnSignalInfo{} , true );
719
680
}
720
681
721
682
// If the vehicle does not shift anymore, we turn off the blinker
722
683
if (
723
684
std::fabs (end_shift_length - current_shift_length) <
724
685
p.turn_signal_remaining_shift_length_threshold ) {
725
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
686
+ return std::make_pair (TurnSignalInfo{} , true );
726
687
}
727
688
728
689
const auto get_command = [](const auto & shift_length) {
@@ -737,7 +698,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
737
698
p.vehicle_info .max_longitudinal_offset_m ;
738
699
739
700
if (signal_prepare_distance < ego_front_to_shift_start) {
740
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , false );
701
+ return std::make_pair (TurnSignalInfo{} , false );
741
702
}
742
703
743
704
const auto blinker_start_pose = path.path .points .at (shift_line.start_idx ).point .pose ;
@@ -754,13 +715,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
754
715
turn_signal_info.turn_signal .command = get_command (relative_shift_length);
755
716
756
717
if (!p.turn_signal_on_swerving ) {
757
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , false );
718
+ return std::make_pair (turn_signal_info , false );
758
719
}
759
720
760
721
lanelet::ConstLanelet lanelet;
761
722
const auto query_pose = (egos_lane_is_shifted) ? shift_line.end : shift_line.start ;
762
723
if (!rh->getClosestLaneletWithinRoute (query_pose, &lanelet)) {
763
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
724
+ return std::make_pair (TurnSignalInfo{} , true );
764
725
}
765
726
766
727
const auto left_same_direction_lane = rh->getLeftLanelet (lanelet, true , true );
@@ -775,13 +736,13 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
775
736
!is_pull_out && !existShiftSideLane (
776
737
start_shift_length, end_shift_length, !has_left_lane, !has_right_lane,
777
738
p.turn_signal_shift_length_threshold )) {
778
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
739
+ return std::make_pair (TurnSignalInfo{} , true );
779
740
}
780
741
781
742
// Check if the ego will cross lane bounds.
782
743
// Note that pull out requires blinkers, even if the ego does not cross lane bounds
783
744
if (!is_pull_out && !straddleRoadBound (path, shift_line, current_lanelets, p.vehicle_info )) {
784
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
745
+ return std::make_pair (TurnSignalInfo{} , true );
785
746
}
786
747
787
748
// If the ego has stopped and its close to completing its shift, turn off the blinkers
@@ -790,7 +751,7 @@ std::pair<TurnSignalInfo, bool> TurnSignalDecider::getBehaviorTurnSignalInfo(
790
751
if (isNearEndOfShift (
791
752
start_shift_length, end_shift_length, ego_pose.position , current_lanelets,
792
753
p.turn_signal_shift_length_threshold )) {
793
- return std::make_pair (TurnSignalInfo (p_path_start, p_path_end) , true );
754
+ return std::make_pair (TurnSignalInfo{} , true );
794
755
}
795
756
}
796
757
0 commit comments