Skip to content

Commit

Permalink
fix(behavior_path_planner): fix functions related to pull over lanes
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Sep 4, 2023
1 parent feb34ed commit 8c32feb
Show file tree
Hide file tree
Showing 9 changed files with 95 additions and 51 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,9 @@ using visualization_msgs::msg::MarkerArray;

// TODO(sugahara) move to util
PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWithLaneId & path2);
lanelet::ConstLanelets getPullOverLanes(const RouteHandler & route_handler, const bool left_side);
lanelet::ConstLanelets getPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance);
PredictedObjects filterObjectsByLateralDistance(
const Pose & ego_pose, const double vehicle_width, const PredictedObjects & objects,
const double distance_thresh, const bool filter_inside);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -327,8 +327,9 @@ bool GoalPlannerModule::isExecutionRequested() const
// if (A) or (B) is met execute pull over
// (A) target lane is `road` and same to the current lanes
// (B) target lane is `road_shoulder` and neighboring to the current lanes
const lanelet::ConstLanelets pull_over_lanes =
goal_planner_utils::getPullOverLanes(*(route_handler), left_side_parking_);
const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
*(route_handler), left_side_parking_, parameters_->backward_goal_search_length,
parameters_->forward_goal_search_length);
lanelet::ConstLanelet target_lane{};
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane);
if (!isCrossingPossible(current_lane, target_lane)) {
Expand Down Expand Up @@ -359,8 +360,9 @@ double GoalPlannerModule::calcModuleRequestLength() const

Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const
{
const lanelet::ConstLanelets pull_over_lanes =
goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
*(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length,
parameters_->forward_goal_search_length);

lanelet::Lanelet closest_pull_over_lanelet{};
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &closest_pull_over_lanelet);
Expand Down Expand Up @@ -612,8 +614,9 @@ void GoalPlannerModule::setLanes()
planner_data_, parameters_->backward_goal_search_length,
parameters_->forward_goal_search_length,
/*forward_only_in_route*/ false);
status_.pull_over_lanes =
goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
status_.pull_over_lanes = goal_planner_utils::getPullOverLanes(
*(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length,
parameters_->forward_goal_search_length);
status_.lanes =
utils::generateDrivableLanesWithShoulderLanes(status_.current_lanes, status_.pull_over_lanes);
}
Expand Down Expand Up @@ -1543,8 +1546,9 @@ bool GoalPlannerModule::checkOriginalGoalIsInShoulder() const
const auto & route_handler = planner_data_->route_handler;
const Pose & goal_pose = route_handler->getGoalPose();

const lanelet::ConstLanelets pull_over_lanes =
goal_planner_utils::getPullOverLanes(*(route_handler), left_side_parking_);
const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
*(route_handler), left_side_parking_, parameters_->backward_goal_search_length,
parameters_->forward_goal_search_length);
lanelet::ConstLanelet target_lane{};
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,9 @@ boost::optional<PullOverPath> FreespacePullOver::plan(const Pose & goal_pose)
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length,
/*forward_only_in_route*/ false);
const auto pull_over_lanes =
goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length,
parameters_.forward_goal_search_length);
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,13 +47,14 @@ boost::optional<PullOverPath> GeometricPullOver::plan(const Pose & goal_pose)
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length,
/*forward_only_in_route*/ false);
const auto shoulder_lanes =
goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_);
if (road_lanes.empty() || shoulder_lanes.empty()) {
const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*route_handler, left_side_parking_, parameters_.backward_goal_search_length,
parameters_.forward_goal_search_length);
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
auto lanes = road_lanes;
lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end());
lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end());

const auto & p = parallel_parking_parameters_;
const double max_steer_angle =
Expand All @@ -62,7 +63,7 @@ boost::optional<PullOverPath> GeometricPullOver::plan(const Pose & goal_pose)
planner_.setPlannerData(planner_data_);

const bool found_valid_path =
planner_.planPullOver(goal_pose, road_lanes, shoulder_lanes, is_forward_);
planner_.planPullOver(goal_pose, road_lanes, pull_over_lanes, is_forward_);
if (!found_valid_path) {
return {};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,9 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose)
const double max_lateral_offset = parameters_.max_lateral_offset;
const double ignore_distance_from_lane_start = parameters_.ignore_distance_from_lane_start;

const auto pull_over_lanes =
goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_);
const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*route_handler, left_side_parking_, parameters_.backward_goal_search_length,
parameters_.forward_goal_search_length);
auto lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_length, forward_length,
/*forward_only_in_route*/ false);
Expand Down Expand Up @@ -150,8 +151,9 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const
}

// check margin with pull over lane objects
const auto pull_over_lanes =
goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length,
parameters_.forward_goal_search_length);
const auto [shoulder_lane_objects, others] =
utils::path_safety_checker::separateObjectsByLanelets(
*(planner_data_->dynamic_object), pull_over_lanes);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,16 +49,16 @@ boost::optional<PullOverPath> ShiftPullOver::plan(const Pose & goal_pose)
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_search_length, forward_search_length,
/*forward_only_in_route*/ false);
const auto shoulder_lanes =
goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_);
if (road_lanes.empty() || shoulder_lanes.empty()) {
const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*route_handler, left_side_parking_, backward_search_length, forward_search_length);
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}

// find safe one from paths with different jerk
for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) {
const auto pull_over_path =
generatePullOverPath(road_lanes, shoulder_lanes, goal_pose, lateral_jerk);
generatePullOverPath(road_lanes, pull_over_lanes, goal_pose, lateral_jerk);
if (!pull_over_path) continue;
return *pull_over_path;
}
Expand Down
22 changes: 9 additions & 13 deletions planning/behavior_path_planner/src/utils/goal_planner/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,36 +55,32 @@ PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWith
return path;
}

lanelet::ConstLanelets getPullOverLanes(const RouteHandler & route_handler, const bool left_side)
lanelet::ConstLanelets getPullOverLanes(
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
const double forward_distance)
{
const Pose goal_pose = route_handler.getGoalPose();

lanelet::ConstLanelet target_shoulder_lane{};
if (route_handler::RouteHandler::getPullOverTarget(
route_handler.getShoulderLanelets(), goal_pose, &target_shoulder_lane)) {
// pull over on shoulder lane
return route_handler.getShoulderLaneletSequence(target_shoulder_lane, goal_pose);
return route_handler.getShoulderLaneletSequence(
target_shoulder_lane, goal_pose, backward_distance, forward_distance);
}

// pull over on road lane
lanelet::ConstLanelet closest_lane{};
route_handler.getClosestLaneletWithinRoute(goal_pose, &closest_lane);

lanelet::ConstLanelet outermost_lane{};
if (left_side) {
outermost_lane = route_handler.getMostLeftLanelet(closest_lane);
outermost_lane = route_handler.getMostLeftLanelet(closest_lane, false, true);
} else {
outermost_lane = route_handler.getMostRightLanelet(closest_lane);
}

lanelet::ConstLanelet outermost_shoulder_lane;
if (route_handler.getLeftShoulderLanelet(outermost_lane, &outermost_shoulder_lane)) {
return route_handler.getShoulderLaneletSequence(outermost_shoulder_lane, goal_pose);
outermost_lane = route_handler.getMostRightLanelet(closest_lane, false, true);
}

const bool dist = std::numeric_limits<double>::max();
constexpr bool only_route_lanes = false;
return route_handler.getLaneletSequence(outermost_lane, dist, dist, only_route_lanes);
return route_handler.getLaneletSequence(
outermost_lane, backward_distance, forward_distance, only_route_lanes);
}

PredictedObjects filterObjectsByLateralDistance(
Expand Down
12 changes: 8 additions & 4 deletions planning/route_handler/include/route_handler/route_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
boost::optional<lanelet::ConstLanelet> getRightLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
const bool get_shoulder_lane = false) const;

/**
* @brief Check if same-direction lane is available at the left side of the lanelet
Expand All @@ -131,7 +132,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
boost::optional<lanelet::ConstLanelet> getLeftLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
const bool get_shoulder_lane = false) const;
lanelet::ConstLanelets getNextLanelets(const lanelet::ConstLanelet & lanelet) const;
lanelet::ConstLanelets getPreviousLanelets(const lanelet::ConstLanelet & lanelet) const;

Expand Down Expand Up @@ -194,7 +196,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
lanelet::ConstLanelet getMostRightLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
const bool get_shoulder_lane = false) const;

/**
* @brief Check if same-direction lane is available at the left side of the lanelet
Expand All @@ -204,7 +207,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
lanelet::ConstLanelet getMostLeftLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
const bool get_shoulder_lane = false) const;

/**
* @brief Searches the furthest linestring to the right side of the lanelet
Expand Down
54 changes: 44 additions & 10 deletions planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -514,7 +514,14 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceAfter(
while (rclcpp::ok() && length < min_length) {
lanelet::ConstLanelet next_lanelet;
if (!getNextLaneletWithinRoute(current_lanelet, &next_lanelet)) {
break;
if (only_route_lanes) {
break;
}
const auto next_lanes = getNextLanelets(current_lanelet);
if (next_lanes.empty()) {
break;
}
next_lanelet = next_lanes.front();
}
// loop check
if (lanelet.id() == next_lanelet.id()) {
Expand Down Expand Up @@ -542,7 +549,14 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceUpTo(
while (rclcpp::ok() && length < min_length) {
lanelet::ConstLanelets candidate_lanelets;
if (!getPreviousLaneletsWithinRoute(current_lanelet, &candidate_lanelets)) {
break;
if (only_route_lanes) {
break;
}
const auto prev_lanes = getPreviousLanelets(current_lanelet);
if (prev_lanes.empty()) {
break;
}
candidate_lanelets = prev_lanes;
}
// loop check
if (std::any_of(
Expand Down Expand Up @@ -940,7 +954,8 @@ bool RouteHandler::isBijectiveConnection(
}

boost::optional<lanelet::ConstLanelet> RouteHandler::getRightLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
const bool get_shoulder_lane) const
{
// right road lanelet of shoulder lanelet
if (isShoulderLanelet(lanelet)) {
Expand All @@ -952,6 +967,14 @@ boost::optional<lanelet::ConstLanelet> RouteHandler::getRightLanelet(
return boost::none;
}

// right shoulder lanelet
if (get_shoulder_lane) {
lanelet::ConstLanelet right_shoulder_lanelet;
if (getRightShoulderLanelet(lanelet, &right_shoulder_lanelet)) {
return right_shoulder_lanelet;
}
}

// routable lane
const auto & right_lane = routing_graph_ptr_->right(lanelet);
if (right_lane) {
Expand Down Expand Up @@ -1012,7 +1035,8 @@ bool RouteHandler::getLeftLaneletWithinRoute(
}

boost::optional<lanelet::ConstLanelet> RouteHandler::getLeftLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
const bool get_shoulder_lane) const
{
// left road lanelet of shoulder lanelet
if (isShoulderLanelet(lanelet)) {
Expand All @@ -1024,6 +1048,14 @@ boost::optional<lanelet::ConstLanelet> RouteHandler::getLeftLanelet(
return boost::none;
}

// left shoulder lanelet
if (get_shoulder_lane) {
lanelet::ConstLanelet left_shoulder_lanelet;
if (getLeftShoulderLanelet(lanelet, &left_shoulder_lanelet)) {
return left_shoulder_lanelet;
}
}

// routable lane
const auto & left_lane = routing_graph_ptr_->left(lanelet);
if (left_lane) {
Expand Down Expand Up @@ -1199,26 +1231,28 @@ lanelet::Lanelets RouteHandler::getLeftOppositeLanelets(const lanelet::ConstLane
}

lanelet::ConstLanelet RouteHandler::getMostRightLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
const bool get_shoulder_lane) const
{
// recursively compute the width of the lanes
const auto & same = getRightLanelet(lanelet, enable_same_root);
const auto & same = getRightLanelet(lanelet, enable_same_root, get_shoulder_lane);

if (same) {
return getMostRightLanelet(same.get(), enable_same_root);
return getMostRightLanelet(same.get(), enable_same_root, get_shoulder_lane);
}

return lanelet;
}

lanelet::ConstLanelet RouteHandler::getMostLeftLanelet(
const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
const bool get_shoulder_lane) const
{
// recursively compute the width of the lanes
const auto & same = getLeftLanelet(lanelet, enable_same_root);
const auto & same = getLeftLanelet(lanelet, enable_same_root, get_shoulder_lane);

if (same) {
return getMostLeftLanelet(same.get(), enable_same_root);
return getMostLeftLanelet(same.get(), enable_same_root, get_shoulder_lane);
}

return lanelet;
Expand Down

0 comments on commit 8c32feb

Please sign in to comment.