Skip to content

Commit fea1945

Browse files
committed
remove LC specific functions from route handler
Signed-off-by: Mohammad <alqudah.mohammad@tier4.jp>
1 parent e157e16 commit fea1945

3 files changed

Lines changed: 0 additions & 98 deletions

File tree

planning/autoware_route_handler/include/autoware/route_handler/route_handler.hpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -311,10 +311,6 @@ class RouteHandler
311311
const lanelet::ConstLanelets & lanelet_sequence,
312312
const size_t piecewise_waypoints_lanelet_sequence_index,
313313
const bool is_removing_direction_forward) const;
314-
std::optional<lanelet::ConstLanelet> getLaneChangeTarget(
315-
const lanelet::ConstLanelets & lanelets, const Direction direction = Direction::NONE) const;
316-
std::optional<lanelet::ConstLanelet> getLaneChangeTargetExceptPreferredLane(
317-
const lanelet::ConstLanelets & lanelets, const Direction direction) const;
318314
std::optional<lanelet::ConstLanelet> getPullOverTarget(const Pose & goal_pose) const;
319315
std::optional<lanelet::ConstLanelet> getPullOutStartLane(
320316
const Pose & pose, const double vehicle_width) const;

planning/autoware_route_handler/src/route_handler.cpp

Lines changed: 0 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -1481,68 +1481,6 @@ std::vector<lanelet::ConstLanelets> RouteHandler::getPrecedingLaneletSequence(
14811481
lanelet, routing_graph_ptr_, length, exclude_lanelets);
14821482
}
14831483

1484-
std::optional<lanelet::ConstLanelet> RouteHandler::getLaneChangeTarget(
1485-
const lanelet::ConstLanelets & lanelets, const Direction direction) const
1486-
{
1487-
for (const auto & lanelet : lanelets) {
1488-
const int num = getNumLaneToPreferredLane(lanelet, direction);
1489-
if (num == 0) {
1490-
continue;
1491-
}
1492-
1493-
if (direction == Direction::NONE || direction == Direction::RIGHT) {
1494-
if (num < 0) {
1495-
const auto right_lanes = routing_graph_ptr_->right(lanelet);
1496-
if (!!right_lanes) {
1497-
return *right_lanes;
1498-
}
1499-
}
1500-
}
1501-
1502-
if (direction == Direction::NONE || direction == Direction::LEFT) {
1503-
if (num > 0) {
1504-
const auto left_lanes = routing_graph_ptr_->left(lanelet);
1505-
if (!!left_lanes) {
1506-
return *left_lanes;
1507-
}
1508-
}
1509-
}
1510-
}
1511-
1512-
return std::nullopt;
1513-
}
1514-
1515-
std::optional<lanelet::ConstLanelet> RouteHandler::getLaneChangeTargetExceptPreferredLane(
1516-
const lanelet::ConstLanelets & lanelets, const Direction direction) const
1517-
{
1518-
for (const auto & lanelet : lanelets) {
1519-
if (direction == Direction::RIGHT) {
1520-
// Get right lanelet if preferred lane is on the left
1521-
if (getNumLaneToPreferredLane(lanelet, direction) < 0) {
1522-
continue;
1523-
}
1524-
1525-
const auto right_lanes = routing_graph_ptr_->right(lanelet);
1526-
if (!!right_lanes) {
1527-
return *right_lanes;
1528-
}
1529-
}
1530-
1531-
if (direction == Direction::LEFT) {
1532-
// Get left lanelet if preferred lane is on the right
1533-
if (getNumLaneToPreferredLane(lanelet, direction) > 0) {
1534-
continue;
1535-
}
1536-
const auto left_lanes = routing_graph_ptr_->left(lanelet);
1537-
if (!!left_lanes) {
1538-
return *left_lanes;
1539-
}
1540-
}
1541-
}
1542-
1543-
return std::nullopt;
1544-
}
1545-
15461484
std::optional<lanelet::ConstLanelet> RouteHandler::getPullOverTarget(const Pose & goal_pose) const
15471485
{
15481486
const lanelet::BasicPoint2d p(goal_pose.position.x, goal_pose.position.y);

planning/autoware_route_handler/test/test_route_handler.cpp

Lines changed: 0 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -266,38 +266,6 @@ TEST_F(TestRouteHandler, getClosestLaneletWithinRouteWhenPointsInRoute)
266266
ASSERT_EQ(get_closest_lanelet_within_route(0.5, 1.75, 0).value(), 4424ul);
267267
}
268268

269-
TEST_F(TestRouteHandler, testGetLaneChangeTargetLanes)
270-
{
271-
{
272-
// The input is within expectation.
273-
// There exist no lane changing lane since both 4770 and 4775 are preferred lane.
274-
const auto current_lanes = route_handler_->getLaneletsFromIds({4770, 4775});
275-
const auto lane_change_lane =
276-
route_handler_->getLaneChangeTarget(current_lanes, Direction::RIGHT);
277-
ASSERT_FALSE(lane_change_lane.has_value());
278-
}
279-
280-
{
281-
// The input is within expectation.
282-
// There exist lane changing lane since 4424 is subset of preferred lane 9598.
283-
const auto current_lanes = route_handler_->getLaneletsFromIds({4775, 4424});
284-
const auto lane_change_lane =
285-
route_handler_->getLaneChangeTarget(current_lanes, Direction::RIGHT);
286-
EXPECT_TRUE(lane_change_lane.has_value());
287-
ASSERT_EQ(lane_change_lane.value().id(), 9598ul);
288-
}
289-
290-
{
291-
// The input is within expectation.
292-
// There is a lane-changing lane. Within the maximum current lanes, there is an alternative lane
293-
// to the preferred lane. Therefore, the lane-changing lane exists.
294-
const auto current_lanes = get_current_lanes();
295-
const auto lane_change_lane = route_handler_->getLaneChangeTarget(current_lanes);
296-
ASSERT_TRUE(lane_change_lane.has_value());
297-
ASSERT_EQ(lane_change_lane.value().id(), 9598ul);
298-
}
299-
}
300-
301269
TEST_F(TestRouteHandler, testGetShoulderLaneletsAtPose)
302270
{
303271
set_route_handler("overlap_map.osm");

0 commit comments

Comments
 (0)