Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(behavior_path_planner): update root lanele if it is not in route lanelet #4360

Merged
merged 3 commits into from
Jul 24, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 9 additions & 3 deletions planning/behavior_path_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -636,15 +636,21 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr<PlannerData> & data)

const auto root_lanelet = updateRootLanelet(data);

// if root_lanelet is not route lanelets, reset root lanelet.
// this can be caused by rerouting.
const auto & route_handler = data->route_handler;
if (!route_handler->isRouteLanelet(root_lanelet_.get())) {
root_lanelet_ = root_lanelet;
return;
}

// check ego is in same lane
if (root_lanelet_.get().id() == root_lanelet.id()) {
return;
}

const auto route_handler = data->route_handler;
const auto next_lanelets = route_handler->getRoutingGraphPtr()->following(root_lanelet_.get());

// check ego is in next lane
const auto next_lanelets = route_handler->getRoutingGraphPtr()->following(root_lanelet_.get());
for (const auto & next : next_lanelets) {
if (next.id() == root_lanelet.id()) {
return;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -325,6 +325,7 @@ class RouteHandler
const lanelet::ConstLanelet & prev_lane, const lanelet::ConstLanelet & next_lane) const;
lanelet::ConstLanelets getShoulderLanelets() const;
bool isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const;
bool isRouteLanelet(const lanelet::ConstLanelet & lanelet) const;

// for path
PathWithLaneId getCenterLinePath(
Expand Down
5 changes: 5 additions & 0 deletions planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1800,6 +1800,11 @@ bool RouteHandler::isShoulderLanelet(const lanelet::ConstLanelet & lanelet) cons
return lanelet::utils::contains(shoulder_lanelets_, lanelet);
}

bool RouteHandler::isRouteLanelet(const lanelet::ConstLanelet & lanelet) const
{
return lanelet::utils::contains(route_lanelets_, lanelet);
}

lanelet::ConstLanelets RouteHandler::getPreviousLaneletSequence(
const lanelet::ConstLanelets & lanelet_sequence) const
{
Expand Down