@@ -893,7 +893,7 @@ std::vector<DrivableLanes> GoalPlannerModule::generateDrivableLanes() const
893
893
return utils::generateDrivableLanesWithShoulderLanes (current_lanes, pull_over_lanes);
894
894
}
895
895
896
- void GoalPlannerModule::setOutput (BehaviorModuleOutput & output) const
896
+ void GoalPlannerModule::setOutput (BehaviorModuleOutput & output)
897
897
{
898
898
output.reference_path = getPreviousModuleOutput ().reference_path ;
899
899
@@ -966,7 +966,7 @@ void GoalPlannerModule::setModifiedGoal(BehaviorModuleOutput & output) const
966
966
}
967
967
}
968
968
969
- void GoalPlannerModule::setTurnSignalInfo (BehaviorModuleOutput & output) const
969
+ void GoalPlannerModule::setTurnSignalInfo (BehaviorModuleOutput & output)
970
970
{
971
971
const auto original_signal = getPreviousModuleOutput ().turn_signal_info ;
972
972
const auto new_signal = calcTurnSignalInfo ();
@@ -1573,43 +1573,98 @@ bool GoalPlannerModule::isOnModifiedGoal() const
1573
1573
parameters_->th_arrived_distance ;
1574
1574
}
1575
1575
1576
- TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo () const
1576
+ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo ()
1577
1577
{
1578
- TurnSignalInfo turn_signal{}; // output
1578
+ const auto path = thread_safe_data_.get_pull_over_path ()->getFullPath ();
1579
+ if (path.points .empty ()) return getPreviousModuleOutput ().turn_signal_info ;
1579
1580
1580
1581
const auto & current_pose = planner_data_->self_odometry ->pose .pose ;
1581
1582
const auto & start_pose = thread_safe_data_.get_pull_over_path ()->start_pose ;
1582
1583
const auto & end_pose = thread_safe_data_.get_pull_over_path ()->end_pose ;
1583
- const auto full_path = thread_safe_data_.get_pull_over_path ()->getFullPath ();
1584
1584
1585
- // calc TurnIndicatorsCommand
1586
- {
1587
- const double distance_to_end =
1588
- calcSignedArcLength (full_path.points , current_pose.position , end_pose.position );
1589
- const bool is_before_end_pose = distance_to_end >= 0.0 ;
1590
- if (is_before_end_pose) {
1591
- if (left_side_parking_) {
1592
- turn_signal.turn_signal .command = TurnIndicatorsCommand::ENABLE_LEFT;
1593
- } else {
1594
- turn_signal.turn_signal .command = TurnIndicatorsCommand::ENABLE_RIGHT;
1595
- }
1596
- } else {
1597
- turn_signal.turn_signal .command = TurnIndicatorsCommand::NO_COMMAND;
1585
+ const auto shift_start_idx = motion_utils::findNearestIndex (path.points , start_pose.position );
1586
+ const auto shift_end_idx = motion_utils::findNearestIndex (path.points , end_pose.position );
1587
+
1588
+ const auto is_ignore_signal = [this ](const lanelet::Id & id) {
1589
+ if (!ignore_signal_.has_value ()) {
1590
+ return false ;
1598
1591
}
1592
+ return ignore_signal_.value () == id;
1593
+ };
1594
+
1595
+ const auto update_ignore_signal = [this ](const lanelet::Id & id, const bool is_ignore) {
1596
+ return is_ignore ? std::make_optional (id) : std::nullopt;
1597
+ };
1598
+
1599
+ const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes (
1600
+ planner_data_, parameters_->backward_goal_search_length ,
1601
+ parameters_->forward_goal_search_length ,
1602
+ /* forward_only_in_route*/ false );
1603
+
1604
+ if (current_lanes.empty ()) {
1605
+ return {};
1599
1606
}
1600
1607
1601
- // calc desired/required start/end point
1602
- {
1603
- // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds
1604
- // before starting pull_over
1605
- turn_signal.desired_start_point =
1606
- last_approval_data_ && hasDecidedPath () ? last_approval_data_->pose : current_pose;
1607
- turn_signal.desired_end_point = end_pose;
1608
- turn_signal.required_start_point = start_pose;
1609
- turn_signal.required_end_point = end_pose;
1608
+ lanelet::Lanelet closest_lanelet;
1609
+ lanelet::utils::query::getClosestLanelet (current_lanes, current_pose, &closest_lanelet);
1610
+
1611
+ if (is_ignore_signal (closest_lanelet.id ())) {
1612
+ return getPreviousModuleOutput ().turn_signal_info ;
1610
1613
}
1611
1614
1612
- return turn_signal;
1615
+ const double current_shift_length =
1616
+ lanelet::utils::getArcCoordinates (current_lanes, current_pose).distance ;
1617
+
1618
+ constexpr bool egos_lane_is_shifted = true ;
1619
+ constexpr bool is_driving_forward = true ;
1620
+
1621
+ constexpr bool is_pull_out = false ;
1622
+ const bool override_ego_stopped_check = std::invoke ([&]() {
1623
+ if (thread_safe_data_.getPullOverPlannerType () == PullOverPlannerType::SHIFT) {
1624
+ return false ;
1625
+ }
1626
+ constexpr double distance_threshold = 1.0 ;
1627
+ const auto stop_point =
1628
+ thread_safe_data_.get_pull_over_path ()->partial_paths .front ().points .back ();
1629
+ const double distance_from_ego_to_stop_point = std::abs (motion_utils::calcSignedArcLength (
1630
+ path.points , stop_point.point .pose .position , current_pose.position ));
1631
+ return distance_from_ego_to_stop_point < distance_threshold;
1632
+ });
1633
+
1634
+ const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo (
1635
+ path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length, is_driving_forward,
1636
+ egos_lane_is_shifted, override_ego_stopped_check, is_pull_out);
1637
+ ignore_signal_ = update_ignore_signal (closest_lanelet.id (), is_ignore);
1638
+
1639
+ return new_signal;
1640
+ // // calc TurnIndicatorsCommand
1641
+ // {
1642
+ // const double distance_to_end =
1643
+ // calcSignedArcLength(full_path.points, current_pose.position, end_pose.position);
1644
+ // const bool is_before_end_pose = distance_to_end >= 0.0;
1645
+ // if (is_before_end_pose) {
1646
+ // if (left_side_parking_) {
1647
+ // turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT;
1648
+ // } else {
1649
+ // turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT;
1650
+ // }
1651
+ // } else {
1652
+ // turn_signal.turn_signal.command = TurnIndicatorsCommand::NO_COMMAND;
1653
+ // }
1654
+ // }
1655
+
1656
+ // // calc desired/required start/end point
1657
+ // {
1658
+ // // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds
1659
+ // // before starting pull_over
1660
+ // turn_signal.desired_start_point =
1661
+ // last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose;
1662
+ // turn_signal.desired_end_point = end_pose;
1663
+ // turn_signal.required_start_point = start_pose;
1664
+ // turn_signal.required_end_point = end_pose;
1665
+ // }
1666
+
1667
+ // return turn_signal;
1613
1668
}
1614
1669
1615
1670
bool GoalPlannerModule::checkOccupancyGridCollision (const PathWithLaneId & path) const
0 commit comments