@@ -508,47 +508,45 @@ BehaviorModuleOutput StartPlannerModule::plan()
508
508
return output;
509
509
}
510
510
511
- PathWithLaneId path;
511
+ const auto path = std::invoke ([&]() {
512
+ if (!status_.driving_forward && !status_.backward_driving_complete ) {
513
+ return status_.backward_path ;
514
+ }
512
515
513
- // Check if backward motion is finished
514
- if (status_.driving_forward || status_.backward_driving_complete ) {
515
516
// Increment path index if the current path is finished
516
517
if (hasFinishedCurrentPath ()) {
517
518
RCLCPP_INFO (getLogger (), " Increment path index" );
518
519
incrementPathIndex ();
519
520
}
520
521
521
- if (!status_.is_safe_dynamic_objects && !isWaitingApproval () && !status_.stop_pose ) {
522
+ if (isWaitingApproval ()) return getCurrentPath ();
523
+
524
+ if (status_.stop_pose ) {
525
+ // Delete stop point if conditions are met
526
+ if (status_.is_safe_dynamic_objects && isStopped ()) {
527
+ status_.stop_pose = std::nullopt;
528
+ }
529
+ stop_pose_ = status_.stop_pose ;
530
+ return *status_.prev_stop_path_after_approval ;
531
+ }
532
+
533
+ if (!status_.is_safe_dynamic_objects ) {
522
534
auto current_path = getCurrentPath ();
523
535
const auto stop_path =
524
536
behavior_path_planner::utils::parking_departure::generateFeasibleStopPath (
525
537
current_path, planner_data_, stop_pose_, parameters_->maximum_deceleration_for_stop ,
526
538
parameters_->maximum_jerk_for_stop );
527
539
540
+ if (!stop_path.has_value ()) return current_path;
528
541
// Insert stop point in the path if needed
529
- if (stop_path) {
530
- RCLCPP_ERROR_THROTTLE (
531
- getLogger (), *clock_, 5000 , " Insert stop point in the path because of dynamic objects" );
532
- path = *stop_path;
533
- status_.prev_stop_path_after_approval = std::make_shared<PathWithLaneId>(path);
534
- status_.stop_pose = stop_pose_;
535
- } else {
536
- path = current_path;
537
- }
538
- } else if (!isWaitingApproval () && status_.stop_pose ) {
539
- // Delete stop point if conditions are met
540
- if (status_.is_safe_dynamic_objects && isStopped ()) {
541
- status_.stop_pose = std::nullopt;
542
- path = getCurrentPath ();
543
- }
544
- path = *status_.prev_stop_path_after_approval ;
545
- stop_pose_ = status_.stop_pose ;
546
- } else {
547
- path = getCurrentPath ();
542
+ RCLCPP_ERROR_THROTTLE (
543
+ getLogger (), *clock_, 5000 , " Insert stop point in the path because of dynamic objects" );
544
+ status_.prev_stop_path_after_approval = std::make_shared<PathWithLaneId>(stop_path.value ());
545
+ status_.stop_pose = stop_pose_;
546
+ return stop_path.value ();
548
547
}
549
- } else {
550
- path = status_.backward_path ;
551
- }
548
+ return getCurrentPath ();
549
+ });
552
550
553
551
output.path = path;
554
552
output.reference_path = getPreviousModuleOutput ().reference_path ;
@@ -768,8 +766,9 @@ bool StartPlannerModule::findPullOutPath(
768
766
const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin)
769
767
{
770
768
// if start_pose_candidate is far from refined_start_pose, backward driving is necessary
769
+ constexpr double epsilon = 0.01 ;
771
770
const bool backward_is_unnecessary =
772
- tier4_autoware_utils::calcDistance2d (start_pose_candidate, refined_start_pose) < 0.01 ;
771
+ tier4_autoware_utils::calcDistance2d (start_pose_candidate, refined_start_pose) < epsilon ;
773
772
774
773
planner->setCollisionCheckMargin (collision_check_margin);
775
774
planner->setPlannerData (planner_data_);
@@ -856,26 +855,24 @@ lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId
856
855
const auto & lanelet_layer = route_handler->getLaneletMapPtr ()->laneletLayer ;
857
856
858
857
std::vector<lanelet::Id> lane_ids;
858
+ lanelet::ConstLanelets path_lanes;
859
+
859
860
for (const auto & p : path.points ) {
860
861
for (const auto & id : p.lane_ids ) {
861
862
if (id == lanelet::InvalId) {
862
863
continue ;
863
864
}
864
- if (route_handler->isShoulderLanelet (lanelet_layer.get (id))) {
865
+ const auto lanelet = lanelet_layer.get (id);
866
+ if (route_handler->isShoulderLanelet (lanelet)) {
865
867
continue ;
866
868
}
867
869
if (std::find (lane_ids.begin (), lane_ids.end (), id) == lane_ids.end ()) {
868
870
lane_ids.push_back (id);
871
+ path_lanes.push_back (lanelet);
869
872
}
870
873
}
871
874
}
872
875
873
- lanelet::ConstLanelets path_lanes;
874
- path_lanes.reserve (lane_ids.size ());
875
- for (const auto & id : lane_ids) {
876
- path_lanes.push_back (lanelet_layer.get (id));
877
- }
878
-
879
876
return path_lanes;
880
877
}
881
878
@@ -954,11 +951,12 @@ void StartPlannerModule::updatePullOutStatus()
954
951
955
952
if (hasFinishedBackwardDriving ()) {
956
953
updateStatusAfterBackwardDriving ();
957
- } else {
958
- status_.backward_path = start_planner_utils::getBackwardPath (
959
- *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose ,
960
- parameters_->backward_velocity );
954
+ return ;
961
955
}
956
+ status_.backward_path = start_planner_utils::getBackwardPath (
957
+ *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose ,
958
+ parameters_->backward_velocity );
959
+ return ;
962
960
}
963
961
964
962
void StartPlannerModule::updateStatusAfterBackwardDriving ()
@@ -1047,7 +1045,7 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
1047
1045
if (distance_from_lane_end < parameters_->ignore_distance_from_lane_end ) {
1048
1046
RCLCPP_WARN_THROTTLE (
1049
1047
getLogger (), *clock_, 5000 ,
1050
- " the ego is too close to the lane end, so needs backward driving" );
1048
+ " the ego vehicle is too close to the lane end, so backwards driving is necessary " );
1051
1049
continue ;
1052
1050
}
1053
1051
@@ -1408,30 +1406,6 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
1408
1406
}
1409
1407
}
1410
1408
1411
- lanelet::ConstLanelets StartPlannerModule::createDepartureCheckLanes () const
1412
- {
1413
- const double backward_path_length =
1414
- planner_data_->parameters .backward_path_length + parameters_->max_back_distance ;
1415
- const auto pull_out_lanes =
1416
- start_planner_utils::getPullOutLanes (planner_data_, backward_path_length);
1417
- if (pull_out_lanes.empty ()) {
1418
- return lanelet::ConstLanelets{};
1419
- }
1420
- const auto road_lanes = utils::getExtendedCurrentLanes (
1421
- planner_data_, backward_path_length, std::numeric_limits<double >::max (),
1422
- /* forward_only_in_route*/ true );
1423
- // extract shoulder lanes from pull out lanes
1424
- lanelet::ConstLanelets shoulder_lanes;
1425
- std::copy_if (
1426
- pull_out_lanes.begin (), pull_out_lanes.end (), std::back_inserter (shoulder_lanes),
1427
- [this ](const auto & pull_out_lane) {
1428
- return planner_data_->route_handler ->isShoulderLanelet (pull_out_lane);
1429
- });
1430
- const auto departure_check_lanes = utils::transformToLanelets (
1431
- utils::generateDrivableLanesWithShoulderLanes (road_lanes, shoulder_lanes));
1432
- return departure_check_lanes;
1433
- }
1434
-
1435
1409
void StartPlannerModule::setDebugData ()
1436
1410
{
1437
1411
using lanelet::visualization::laneletsAsTriangleMarkerArray;
0 commit comments