@@ -1259,11 +1259,13 @@ lanelet::ConstLanelets getCurrentLanesFromPath(
1259
1259
throw std::logic_error (" empty path." );
1260
1260
}
1261
1261
1262
- if (path.points .front ().lane_ids .empty ()) {
1262
+ const auto idx = planner_data->findEgoIndex (path.points );
1263
+
1264
+ if (path.points .at (idx).lane_ids .empty ()) {
1263
1265
throw std::logic_error (" empty lane ids." );
1264
1266
}
1265
1267
1266
- const auto start_id = path.points .front ( ).lane_ids .front ();
1268
+ const auto start_id = path.points .at (idx ).lane_ids .front ();
1267
1269
const auto start_lane = planner_data->route_handler ->getLaneletsFromId (start_id);
1268
1270
const auto & p = planner_data->parameters ;
1269
1271
@@ -1810,6 +1812,7 @@ AvoidLineArray combineRawShiftLinesWithUniqueCheck(
1810
1812
}
1811
1813
1812
1814
lanelet::ConstLanelets getAdjacentLane (
1815
+ const lanelet::ConstLanelet & current_lane,
1813
1816
const std::shared_ptr<const PlannerData> & planner_data,
1814
1817
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift)
1815
1818
{
@@ -1818,18 +1821,17 @@ lanelet::ConstLanelets getAdjacentLane(
1818
1821
const auto & backward_distance = parameters->safety_check_backward_distance ;
1819
1822
const auto & vehicle_pose = planner_data->self_odometry ->pose .pose ;
1820
1823
1821
- lanelet::ConstLanelet current_lane;
1822
- if (!rh->getClosestLaneletWithinRoute (vehicle_pose, ¤t_lane)) {
1823
- RCLCPP_ERROR (
1824
- rclcpp::get_logger (" behavior_path_planner" ).get_child (" avoidance" ),
1825
- " failed to find closest lanelet within route!!!" );
1826
- return {}; // TODO(Satoshi Ota)
1827
- }
1828
-
1829
1824
const auto ego_succeeding_lanes =
1830
1825
rh->getLaneletSequence (current_lane, vehicle_pose, backward_distance, forward_distance);
1831
1826
1832
1827
lanelet::ConstLanelets lanes{};
1828
+
1829
+ const auto exist = [&lanes](const auto id) {
1830
+ const auto itr = std::find_if (
1831
+ lanes.begin (), lanes.end (), [&id](const auto & lane) { return lane.id () == id; });
1832
+ return itr != lanes.end ();
1833
+ };
1834
+
1833
1835
for (const auto & lane : ego_succeeding_lanes) {
1834
1836
const auto opt_left_lane = rh->getLeftLanelet (lane, true , false );
1835
1837
if (!is_right_shift && opt_left_lane) {
@@ -1844,6 +1846,20 @@ lanelet::ConstLanelets getAdjacentLane(
1844
1846
const auto right_opposite_lanes = rh->getRightOppositeLanelets (lane);
1845
1847
if (is_right_shift && !right_opposite_lanes.empty ()) {
1846
1848
lanes.push_back (right_opposite_lanes.front ());
1849
+
1850
+ for (const auto & prev_lane : rh->getPreviousLanelets (right_opposite_lanes.front ())) {
1851
+ if (!exist (prev_lane.id ())) {
1852
+ lanes.push_back (prev_lane);
1853
+ }
1854
+ }
1855
+ }
1856
+ }
1857
+
1858
+ for (const auto & lane : lanes) {
1859
+ for (const auto & next_lane : rh->getNextLanelets (lane)) {
1860
+ if (!exist (next_lane.id ())) {
1861
+ lanes.push_back (next_lane);
1862
+ }
1847
1863
}
1848
1864
}
1849
1865
@@ -1852,14 +1868,14 @@ lanelet::ConstLanelets getAdjacentLane(
1852
1868
1853
1869
std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects (
1854
1870
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data,
1855
- const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift ,
1856
- DebugData & debug)
1871
+ const std::shared_ptr<AvoidanceParameters> & parameters, const bool has_left_shift ,
1872
+ const bool has_right_shift, DebugData & debug)
1857
1873
{
1858
1874
const auto & p = parameters;
1859
1875
const auto check_right_lanes =
1860
- (is_right_shift && p->check_shift_side_lane ) || (!is_right_shift && p->check_other_side_lane );
1876
+ (has_right_shift && p->check_shift_side_lane ) || (has_left_shift && p->check_other_side_lane );
1861
1877
const auto check_left_lanes =
1862
- (!is_right_shift && p->check_shift_side_lane ) || (is_right_shift && p->check_other_side_lane );
1878
+ (has_left_shift && p->check_shift_side_lane ) || (has_right_shift && p->check_other_side_lane );
1863
1879
1864
1880
std::vector<ExtendedPredictedObject> target_objects;
1865
1881
@@ -1897,9 +1913,16 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
1897
1913
return ret;
1898
1914
}();
1899
1915
1916
+ lanelet::ConstLanelet closest_lanelet;
1917
+ const auto & ego_pose = planner_data->self_odometry ->pose .pose ;
1918
+ if (!lanelet::utils::query::getClosestLanelet (
1919
+ data.current_lanelets , ego_pose, &closest_lanelet)) {
1920
+ return {};
1921
+ }
1922
+
1900
1923
// check right lanes
1901
1924
if (check_right_lanes) {
1902
- const auto check_lanes = getAdjacentLane (planner_data, p, true );
1925
+ const auto check_lanes = getAdjacentLane (closest_lanelet, planner_data, p, true );
1903
1926
1904
1927
if (p->check_other_object ) {
1905
1928
const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets (
@@ -1921,7 +1944,7 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
1921
1944
1922
1945
// check left lanes
1923
1946
if (check_left_lanes) {
1924
- const auto check_lanes = getAdjacentLane (planner_data, p, false );
1947
+ const auto check_lanes = getAdjacentLane (closest_lanelet, planner_data, p, false );
1925
1948
1926
1949
if (p->check_other_object ) {
1927
1950
const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets (
0 commit comments