@@ -140,6 +140,46 @@ LaneChangePath NormalLaneChange::getLaneChangePath() const
140
140
return status_.lane_change_path ;
141
141
}
142
142
143
+ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath () const
144
+ {
145
+ BehaviorModuleOutput output;
146
+
147
+ const auto current_lanes = getCurrentLanes ();
148
+ if (current_lanes.empty ()) {
149
+ RCLCPP_WARN (logger_, " Current lanes not found!!! Something wrong." );
150
+ output.path = prev_module_path_;
151
+ output.reference_path = prev_module_reference_path_;
152
+ output.drivable_area_info = prev_drivable_area_info_;
153
+ output.turn_signal_info = prev_turn_signal_info_;
154
+ return output;
155
+ }
156
+
157
+ const auto terminal_path =
158
+ calcTerminalLaneChangePath (current_lanes, getLaneChangeLanes (current_lanes, direction_));
159
+ if (!terminal_path) {
160
+ RCLCPP_WARN (logger_, " Terminal path not found!!!" );
161
+ output.path = prev_module_path_;
162
+ output.reference_path = prev_module_reference_path_;
163
+ output.drivable_area_info = prev_drivable_area_info_;
164
+ output.turn_signal_info = prev_turn_signal_info_;
165
+ return output;
166
+ }
167
+
168
+ output.path = terminal_path->path ;
169
+ output.reference_path = prev_module_reference_path_;
170
+ output.turn_signal_info = updateOutputTurnSignal ();
171
+
172
+ extendOutputDrivableArea (output);
173
+
174
+ const auto current_seg_idx = planner_data_->findEgoSegmentIndex (output.path .points );
175
+ output.turn_signal_info = planner_data_->turn_signal_decider .use_prior_turn_signal (
176
+ output.path , getEgoPose (), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info ,
177
+ planner_data_->parameters .ego_nearest_dist_threshold ,
178
+ planner_data_->parameters .ego_nearest_yaw_threshold );
179
+
180
+ return output;
181
+ }
182
+
143
183
BehaviorModuleOutput NormalLaneChange::generateOutput ()
144
184
{
145
185
BehaviorModuleOutput output;
@@ -840,6 +880,10 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
840
880
const auto current_pose = getEgoPose ();
841
881
const auto & route_handler = *getRouteHandler ();
842
882
const auto & common_parameters = planner_data_->parameters ;
883
+ const auto shift_intervals =
884
+ route_handler.getLateralIntervalsToPreferredLane (current_lanes.back (), direction_);
885
+ const double minimum_lane_change_length =
886
+ utils::lane_change::calcMinimumLaneChangeLength (*lane_change_parameters_, shift_intervals);
843
887
844
888
// Guard
845
889
if (objects.objects .empty ()) {
@@ -909,6 +953,24 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
909
953
return std::abs (lateral) > (common_parameters.vehicle_width / 2 );
910
954
};
911
955
956
+ // ignore object that are ahead of terminal lane change start
957
+ {
958
+ double distance_to_terminal_from_object = std::numeric_limits<double >::max ();
959
+ for (const auto & polygon_p : obj_polygon_outer) {
960
+ const auto obj_p = tier4_autoware_utils::createPoint (polygon_p.x (), polygon_p.y (), 0.0 );
961
+ Pose polygon_pose;
962
+ polygon_pose.position = obj_p;
963
+ polygon_pose.orientation = object.kinematics .initial_pose_with_covariance .pose .orientation ;
964
+ const double dist = utils::getDistanceToEndOfLane (polygon_pose, current_lanes);
965
+ if (dist < distance_to_terminal_from_object) {
966
+ distance_to_terminal_from_object = dist;
967
+ }
968
+ }
969
+ if (minimum_lane_change_length > distance_to_terminal_from_object) {
970
+ continue ;
971
+ }
972
+ }
973
+
912
974
// ignore static object that are behind the ego vehicle
913
975
if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0 ) {
914
976
continue ;
@@ -1416,6 +1478,151 @@ bool NormalLaneChange::getLaneChangePaths(
1416
1478
return false ;
1417
1479
}
1418
1480
1481
+ std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath (
1482
+ const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const
1483
+ {
1484
+ if (current_lanes.empty () || target_lanes.empty ()) {
1485
+ RCLCPP_WARN (logger_, " target_neighbor_preferred_lane_poly_2d is empty. Not expected." );
1486
+ return {};
1487
+ }
1488
+ const auto & route_handler = *getRouteHandler ();
1489
+ const auto & common_parameters = planner_data_->parameters ;
1490
+
1491
+ const auto forward_path_length = common_parameters.forward_path_length ;
1492
+ const auto minimum_lane_changing_velocity =
1493
+ lane_change_parameters_->minimum_lane_changing_velocity ;
1494
+
1495
+ const auto is_goal_in_route = route_handler.isInGoalRouteSection (target_lanes.back ());
1496
+
1497
+ const double lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength (
1498
+ *lane_change_parameters_,
1499
+ route_handler.getLateralIntervalsToPreferredLane (current_lanes.back ()));
1500
+ const double next_lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength (
1501
+ *lane_change_parameters_,
1502
+ route_handler.getLateralIntervalsToPreferredLane (target_lanes.back ()));
1503
+
1504
+ const auto target_lane_length = lanelet::utils::getLaneletLength2d (target_lanes);
1505
+
1506
+ const auto sorted_lane_ids =
1507
+ utils::lane_change::getSortedLaneIds (route_handler, getEgoPose (), current_lanes, target_lanes);
1508
+
1509
+ const auto target_neighbor_preferred_lane_poly_2d =
1510
+ utils::lane_change::getTargetNeighborLanesPolygon (route_handler, current_lanes, type_);
1511
+ if (target_neighbor_preferred_lane_poly_2d.empty ()) {
1512
+ RCLCPP_WARN (logger_, " target_neighbor_preferred_lane_poly_2d is empty. Not expected." );
1513
+ return {};
1514
+ }
1515
+
1516
+ // lane changing start getEgoPose() is at the end of prepare segment
1517
+ const auto current_lane_terminal_point =
1518
+ lanelet::utils::conversion::toGeomMsgPt (current_lanes.back ().centerline3d ().back ());
1519
+
1520
+ double distance_to_terminal_from_goal = 0 ;
1521
+ if (is_goal_in_route) {
1522
+ distance_to_terminal_from_goal =
1523
+ utils::getDistanceToEndOfLane (route_handler.getGoalPose (), current_lanes);
1524
+ }
1525
+
1526
+ const auto lane_changing_start_pose = motion_utils::calcLongitudinalOffsetPose (
1527
+ prev_module_path_.points , current_lane_terminal_point,
1528
+ -(lane_change_buffer + next_lane_change_buffer + distance_to_terminal_from_goal));
1529
+
1530
+ if (!lane_changing_start_pose) {
1531
+ RCLCPP_WARN (logger_, " Reject: lane changing start pose not found!!!" );
1532
+ return {};
1533
+ }
1534
+
1535
+ const auto target_length_from_lane_change_start_pose = utils::getArcLengthToTargetLanelet (
1536
+ current_lanes, target_lanes.front (), lane_changing_start_pose.value ());
1537
+
1538
+ // Check if the lane changing start point is not on the lanes next to target lanes,
1539
+ if (target_length_from_lane_change_start_pose > 0.0 ) {
1540
+ RCLCPP_WARN (logger_, " lane change start getEgoPose() is behind target lanelet!" );
1541
+ return {};
1542
+ }
1543
+
1544
+ const auto shift_length = lanelet::utils::getLateralDistanceToClosestLanelet (
1545
+ target_lanes, lane_changing_start_pose.value ());
1546
+
1547
+ const auto [min_lateral_acc, max_lateral_acc] =
1548
+ lane_change_parameters_->lane_change_lat_acc_map .find (minimum_lane_changing_velocity);
1549
+
1550
+ const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk (
1551
+ shift_length, lane_change_parameters_->lane_changing_lateral_jerk , max_lateral_acc);
1552
+
1553
+ const auto target_segment = getTargetSegment (
1554
+ target_lanes, lane_changing_start_pose.value (), target_lane_length, lane_change_buffer,
1555
+ minimum_lane_changing_velocity, next_lane_change_buffer);
1556
+
1557
+ if (target_segment.points .empty ()) {
1558
+ RCLCPP_WARN (logger_, " Reject: target segment is empty!! something wrong..." );
1559
+ return {};
1560
+ }
1561
+
1562
+ const lanelet::BasicPoint2d lc_start_point (
1563
+ lane_changing_start_pose->position .x , lane_changing_start_pose->position .y );
1564
+
1565
+ const auto target_lane_polygon =
1566
+ lanelet::utils::getPolygonFromArcLength (target_lanes, 0 , std::numeric_limits<double >::max ());
1567
+ const auto target_lane_poly_2d = lanelet::utils::to2D (target_lane_polygon).basicPolygon ();
1568
+
1569
+ const auto is_valid_start_point =
1570
+ boost::geometry::covered_by (lc_start_point, target_neighbor_preferred_lane_poly_2d) ||
1571
+ boost::geometry::covered_by (lc_start_point, target_lane_poly_2d);
1572
+
1573
+ LaneChangeInfo lane_change_info;
1574
+ lane_change_info.longitudinal_acceleration = LaneChangePhaseInfo{0.0 , 0.0 };
1575
+ lane_change_info.duration = LaneChangePhaseInfo{0.0 , lane_changing_time};
1576
+ lane_change_info.velocity =
1577
+ LaneChangePhaseInfo{minimum_lane_changing_velocity, minimum_lane_changing_velocity};
1578
+ lane_change_info.length = LaneChangePhaseInfo{0.0 , lane_change_buffer};
1579
+ lane_change_info.current_lanes = current_lanes;
1580
+ lane_change_info.target_lanes = target_lanes;
1581
+ lane_change_info.lane_changing_start = lane_changing_start_pose.value ();
1582
+ lane_change_info.lane_changing_end = target_segment.points .front ().point .pose ;
1583
+ lane_change_info.lateral_acceleration = max_lateral_acc;
1584
+ lane_change_info.terminal_lane_changing_velocity = minimum_lane_changing_velocity;
1585
+
1586
+ if (!is_valid_start_point) {
1587
+ RCLCPP_WARN (
1588
+ logger_,
1589
+ " Reject: lane changing points are not inside of the target preferred lanes or its "
1590
+ " neighbors" );
1591
+ return {};
1592
+ }
1593
+
1594
+ const auto resample_interval = utils::lane_change::calcLaneChangeResampleInterval (
1595
+ lane_change_buffer, minimum_lane_changing_velocity);
1596
+ const auto target_lane_reference_path = utils::lane_change::getReferencePathFromTargetLane (
1597
+ route_handler, target_lanes, lane_changing_start_pose.value (), target_lane_length,
1598
+ lane_change_buffer, forward_path_length, resample_interval, is_goal_in_route,
1599
+ next_lane_change_buffer);
1600
+
1601
+ if (target_lane_reference_path.points .empty ()) {
1602
+ RCLCPP_WARN (logger_, " Reject: target_lane_reference_path is empty!!" );
1603
+ return {};
1604
+ }
1605
+
1606
+ lane_change_info.shift_line = utils::lane_change::getLaneChangingShiftLine (
1607
+ lane_changing_start_pose.value (), target_segment.points .front ().point .pose ,
1608
+ target_lane_reference_path, shift_length);
1609
+
1610
+ auto reference_segment = prev_module_path_;
1611
+ const double length_to_lane_changing_start = motion_utils::calcSignedArcLength (
1612
+ reference_segment.points , reference_segment.points .front ().point .pose .position ,
1613
+ lane_changing_start_pose->position );
1614
+ utils::clipPathLength (reference_segment, 0 , length_to_lane_changing_start, 0.0 );
1615
+ // remove terminal points because utils::clipPathLength() calculates extra long path
1616
+ reference_segment.points .pop_back ();
1617
+ reference_segment.points .back ().point .longitudinal_velocity_mps = minimum_lane_changing_velocity;
1618
+
1619
+ const auto terminal_lane_change_path = utils::lane_change::constructCandidatePath (
1620
+ lane_change_info, reference_segment, target_segment, target_lane_reference_path,
1621
+ sorted_lane_ids);
1622
+
1623
+ return terminal_lane_change_path;
1624
+ }
1625
+
1419
1626
PathSafetyStatus NormalLaneChange::isApprovedPathSafe () const
1420
1627
{
1421
1628
const auto & path = status_.lane_change_path ;
@@ -1467,6 +1674,10 @@ TurnSignalInfo NormalLaneChange::calcTurnSignalInfo() const
1467
1674
1468
1675
TurnSignalInfo turn_signal_info{};
1469
1676
1677
+ if (path.path .points .empty ()) {
1678
+ return turn_signal_info;
1679
+ }
1680
+
1470
1681
// desired start pose = prepare start pose
1471
1682
turn_signal_info.desired_start_point = std::invoke ([&]() {
1472
1683
const auto blinker_start_duration = planner_data_->parameters .turn_signal_search_time ;
0 commit comments