Skip to content

Commit f51def1

Browse files
author
beyza
committed
consider all overlap lanelets as a goal lanelet
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 7d8ee41 commit f51def1

File tree

2 files changed

+70
-56
lines changed

2 files changed

+70
-56
lines changed

planning/mission_planner/src/lanelet2_plugins/default_planner.cpp

+29-21
Original file line numberDiff line numberDiff line change
@@ -339,9 +339,13 @@ bool DefaultPlanner::is_goal_valid(
339339
}
340340
}
341341

342-
lanelet::Lanelet closest_lanelet;
343-
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &closest_lanelet)) {
344-
return false;
342+
lanelet::ConstLanelet goal_lanelet;
343+
lanelet::ConstLanelets goal_lanelets;
344+
if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, goal, &goal_lanelets)) {
345+
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &goal_lanelet)) {
346+
return false;
347+
}
348+
goal_lanelets = {goal_lanelet};
345349
}
346350

347351
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
@@ -351,30 +355,34 @@ bool DefaultPlanner::is_goal_valid(
351355
const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint);
352356

353357
double next_lane_length = 0.0;
358+
bool is_goal_valid = false;
354359
// combine calculated route lanelets
355360
lanelet::ConstLanelet combined_prev_lanelet =
356361
combine_lanelets_with_shoulder(path_lanelets, shoulder_lanelets_);
357362

358363
// check if goal footprint exceeds lane when the goal isn't in parking_lot
359-
if (
360-
param_.check_footprint_inside_lanes &&
361-
!check_goal_footprint(
362-
closest_lanelet, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
363-
!is_in_parking_lot(
364-
lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_),
365-
lanelet::utils::conversion::toLaneletPoint(goal.position))) {
366-
RCLCPP_WARN(logger, "Goal's footprint exceeds lane!");
367-
return false;
368-
}
364+
for (const auto & gl_llt : goal_lanelets) {
365+
if (
366+
param_.check_footprint_inside_lanes &&
367+
!check_goal_footprint(gl_llt, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
368+
!is_in_parking_lot(
369+
lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_),
370+
lanelet::utils::conversion::toLaneletPoint(goal.position))) {
371+
RCLCPP_WARN(logger, "Goal's footprint exceeds lane!");
372+
is_goal_valid = false;
373+
} else {
374+
is_goal_valid = true;
375+
}
369376

370-
if (is_in_lane(closest_lanelet, goal_lanelet_pt)) {
371-
const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet, goal.position);
372-
const auto goal_yaw = tf2::getYaw(goal.orientation);
373-
const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw);
377+
if (is_in_lane(gl_llt, goal_lanelet_pt)) {
378+
const auto lane_yaw = lanelet::utils::getLaneletAngle(gl_llt, goal.position);
379+
const auto goal_yaw = tf2::getYaw(goal.orientation);
380+
const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw);
374381

375-
const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg);
376-
if (std::abs(angle_diff) < th_angle) {
377-
return true;
382+
const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg);
383+
if (std::abs(angle_diff) < th_angle) {
384+
return true;
385+
}
378386
}
379387
}
380388

@@ -390,7 +398,7 @@ bool DefaultPlanner::is_goal_valid(
390398
return true;
391399
}
392400

393-
return false;
401+
return is_goal_valid;
394402
}
395403

396404
PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points)

planning/route_handler/src/route_handler.cpp

+41-35
Original file line numberDiff line numberDiff line change
@@ -2114,13 +2114,17 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
21142114

21152115
// Find lanelets for goal point.
21162116
lanelet::ConstLanelet goal_lanelet;
2117-
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2118-
RCLCPP_WARN_STREAM(
2119-
logger_, "Failed to find closest lanelet."
2120-
<< std::endl
2121-
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2122-
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl);
2123-
return false;
2117+
lanelet::ConstLanelets goal_lanelets;
2118+
if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, goal_checkpoint, &goal_lanelets)) {
2119+
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2120+
RCLCPP_WARN_STREAM(
2121+
logger_, "Failed to find current lanelet."
2122+
<< std::endl
2123+
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2124+
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl);
2125+
return false;
2126+
}
2127+
goal_lanelets = {goal_lanelet};
21242128
}
21252129

21262130
lanelet::Optional<lanelet::routing::Route> optional_route;
@@ -2133,36 +2137,38 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
21332137
double shortest_path_length2d = std::numeric_limits<double>::max();
21342138

21352139
for (const auto & st_llt : start_lanelets) {
2136-
// check if the angle difference between start_checkpoint and start lanelet center line
2137-
// orientation is in yaw_threshold range
2138-
double yaw_threshold = M_PI / 2.0;
2139-
bool is_proper_angle = false;
2140-
{
2141-
double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position);
2142-
double pose_yaw = tf2::getYaw(start_checkpoint.orientation);
2143-
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));
2144-
2145-
if (angle_diff <= std::abs(yaw_threshold)) {
2146-
is_proper_angle = true;
2140+
for (const auto & gl_llt : goal_lanelets) {
2141+
// check if the angle difference between start_checkpoint and start lanelet center line
2142+
// orientation is in yaw_threshold range
2143+
double yaw_threshold = M_PI / 2.0;
2144+
bool is_proper_angle = false;
2145+
{
2146+
double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position);
2147+
double pose_yaw = tf2::getYaw(start_checkpoint.orientation);
2148+
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));
2149+
2150+
if (angle_diff <= std::abs(yaw_threshold)) {
2151+
is_proper_angle = true;
2152+
}
21472153
}
2148-
}
2149-
2150-
optional_route = routing_graph_ptr_->getRoute(st_llt, goal_lanelet, 0);
2151-
if (!optional_route || !is_proper_angle) {
2152-
RCLCPP_ERROR_STREAM(
2153-
logger_, "Failed to find a proper route!"
2154-
<< std::endl
2155-
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2156-
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl
2157-
<< " - start lane id: " << st_llt.id() << std::endl
2158-
<< " - goal lane id: " << goal_lanelet.id() << std::endl);
2159-
} else {
2160-
is_route_found = true;
21612154

2162-
if (optional_route->length2d() < shortest_path_length2d) {
2163-
shortest_path_length2d = optional_route->length2d();
2164-
shortest_path = optional_route->shortestPath();
2165-
start_lanelet = st_llt;
2155+
optional_route = routing_graph_ptr_->getRoute(st_llt, gl_llt, 0);
2156+
if (!optional_route || !is_proper_angle) {
2157+
RCLCPP_ERROR_STREAM(
2158+
logger_, "Failed to find a proper route!"
2159+
<< std::endl
2160+
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2161+
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl
2162+
<< " - start lane id: " << st_llt.id() << std::endl
2163+
<< " - goal lane id: " << gl_llt.id() << std::endl);
2164+
} else {
2165+
is_route_found = true;
2166+
if (optional_route->length2d() < shortest_path_length2d) {
2167+
shortest_path_length2d = optional_route->length2d();
2168+
shortest_path = optional_route->shortestPath();
2169+
start_lanelet = st_llt;
2170+
goal_lanelet = gl_llt;
2171+
}
21662172
}
21672173
}
21682174
}

0 commit comments

Comments
 (0)