Skip to content

Commit 84a591e

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

File tree

2 files changed

+73
-46
lines changed

2 files changed

+73
-46
lines changed

planning/mission_planner/src/lanelet2_plugins/default_planner.cpp

+29-21
Original file line numberDiff line numberDiff line change
@@ -331,9 +331,13 @@ bool DefaultPlanner::is_goal_valid(
331331
}
332332
}
333333

334-
lanelet::Lanelet closest_lanelet;
335-
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &closest_lanelet)) {
336-
return false;
334+
lanelet::ConstLanelet goal_lanelet;
335+
lanelet::ConstLanelets goal_lanelets;
336+
if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, goal, &goal_lanelets)) {
337+
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &goal_lanelet)) {
338+
return false;
339+
}
340+
goal_lanelets = {goal_lanelet};
337341
}
338342

339343
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
@@ -343,30 +347,34 @@ bool DefaultPlanner::is_goal_valid(
343347
const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint);
344348

345349
double next_lane_length = 0.0;
350+
bool is_goal_valid = false;
346351
// combine calculated route lanelets
347352
const lanelet::ConstLanelet combined_prev_lanelet =
348353
combine_lanelets_with_shoulder(path_lanelets, shoulder_lanelets_);
349354

350355
// check if goal footprint exceeds lane when the goal isn't in parking_lot
351-
if (
352-
param_.check_footprint_inside_lanes &&
353-
!check_goal_footprint_inside_lanes(
354-
closest_lanelet, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
355-
!is_in_parking_lot(
356-
lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_),
357-
lanelet::utils::conversion::toLaneletPoint(goal.position))) {
358-
RCLCPP_WARN(logger, "Goal's footprint exceeds lane!");
359-
return false;
360-
}
356+
for (const auto & gl_llt : goal_lanelets) {
357+
if (
358+
param_.check_footprint_inside_lanes &&
359+
!check_goal_footprint(gl_llt, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
360+
!is_in_parking_lot(
361+
lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_),
362+
lanelet::utils::conversion::toLaneletPoint(goal.position))) {
363+
RCLCPP_WARN(logger, "Goal's footprint exceeds lane!");
364+
is_goal_valid = false;
365+
} else {
366+
is_goal_valid = true;
367+
}
361368

362-
if (is_in_lane(closest_lanelet, goal_lanelet_pt)) {
363-
const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet, goal.position);
364-
const auto goal_yaw = tf2::getYaw(goal.orientation);
365-
const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw);
369+
if (is_in_lane(gl_llt, goal_lanelet_pt)) {
370+
const auto lane_yaw = lanelet::utils::getLaneletAngle(gl_llt, goal.position);
371+
const auto goal_yaw = tf2::getYaw(goal.orientation);
372+
const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw);
366373

367-
const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg);
368-
if (std::abs(angle_diff) < th_angle) {
369-
return true;
374+
const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg);
375+
if (std::abs(angle_diff) < th_angle) {
376+
return true;
377+
}
370378
}
371379
}
372380

@@ -382,7 +390,7 @@ bool DefaultPlanner::is_goal_valid(
382390
return true;
383391
}
384392

385-
return false;
393+
return is_goal_valid;
386394
}
387395

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

planning/route_handler/src/route_handler.cpp

+44-25
Original file line numberDiff line numberDiff line change
@@ -2141,13 +2141,17 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
21412141

21422142
// Find lanelets for goal point.
21432143
lanelet::ConstLanelet goal_lanelet;
2144-
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2145-
RCLCPP_WARN_STREAM(
2146-
logger_, "Failed to find closest lanelet."
2147-
<< std::endl
2148-
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2149-
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl);
2150-
return false;
2144+
lanelet::ConstLanelets goal_lanelets;
2145+
if (!lanelet::utils::query::getCurrentLanelets(road_lanelets_, goal_checkpoint, &goal_lanelets)) {
2146+
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2147+
RCLCPP_WARN_STREAM(
2148+
logger_, "Failed to find current lanelet."
2149+
<< std::endl
2150+
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2151+
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl);
2152+
return false;
2153+
}
2154+
goal_lanelets = {goal_lanelet};
21512155
}
21522156

21532157
lanelet::Optional<lanelet::routing::Route> optional_route;
@@ -2159,24 +2163,39 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
21592163
constexpr double yaw_threshold = M_PI / 2.0;
21602164

21612165
for (const auto & st_llt : start_lanelets) {
2162-
// check if the angle difference between start_checkpoint and start lanelet center line
2163-
// orientation is in yaw_threshold range
2164-
double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position);
2165-
double pose_yaw = tf2::getYaw(start_checkpoint.orientation);
2166-
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));
2167-
2168-
bool is_proper_angle = angle_diff <= std::abs(yaw_threshold);
2169-
2170-
optional_route = routing_graph_ptr_->getRoute(st_llt, goal_lanelet, 0);
2171-
if (!optional_route || !is_proper_angle) {
2172-
RCLCPP_ERROR_STREAM(
2173-
logger_, "Failed to find a proper route!"
2174-
<< std::endl
2175-
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2176-
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl
2177-
<< " - start lane id: " << st_llt.id() << std::endl
2178-
<< " - goal lane id: " << goal_lanelet.id() << std::endl);
2179-
continue;
2166+
for (const auto & gl_llt : goal_lanelets) {
2167+
// check if the angle difference between start_checkpoint and start lanelet center line
2168+
// orientation is in yaw_threshold range
2169+
double yaw_threshold = M_PI / 2.0;
2170+
bool is_proper_angle = false;
2171+
{
2172+
double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position);
2173+
double pose_yaw = tf2::getYaw(start_checkpoint.orientation);
2174+
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));
2175+
2176+
if (angle_diff <= std::abs(yaw_threshold)) {
2177+
is_proper_angle = true;
2178+
}
2179+
}
2180+
2181+
optional_route = routing_graph_ptr_->getRoute(st_llt, gl_llt, 0);
2182+
if (!optional_route || !is_proper_angle) {
2183+
RCLCPP_ERROR_STREAM(
2184+
logger_, "Failed to find a proper route!"
2185+
<< std::endl
2186+
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
2187+
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl
2188+
<< " - start lane id: " << st_llt.id() << std::endl
2189+
<< " - goal lane id: " << gl_llt.id() << std::endl);
2190+
} else {
2191+
is_route_found = true;
2192+
if (optional_route->length2d() < shortest_path_length2d) {
2193+
shortest_path_length2d = optional_route->length2d();
2194+
shortest_path = optional_route->shortestPath();
2195+
start_lanelet = st_llt;
2196+
goal_lanelet = gl_llt;
2197+
}
2198+
}
21802199
}
21812200
is_route_found = true;
21822201
if (angle_diff < smallest_angle_diff) {

0 commit comments

Comments
 (0)