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

revert(behavior_path): revert removal of refineGoalFunction (#2340)" #2485

Merged
merged 1 commit into from
Dec 9, 2022
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
Original file line number Diff line number Diff line change
Expand Up @@ -886,8 +886,18 @@ PathWithLaneId BehaviorPathPlannerNode::modifyPathForSmoothGoalConnection(
const auto goal = planner_data_->route_handler->getGoalPose();
const auto goal_lane_id = planner_data_->route_handler->getGoalLaneId();

Pose refined_goal{};
{
lanelet::ConstLanelet goal_lanelet;
if (planner_data_->route_handler->getGoalLanelet(&goal_lanelet)) {
refined_goal = util::refineGoal(goal, goal_lanelet);
} else {
refined_goal = goal;
}
}

auto refined_path = util::refinePathForGoal(
planner_data_->parameters.refine_goal_search_radius_range, M_PI * 0.5, path, goal,
planner_data_->parameters.refine_goal_search_radius_range, M_PI * 0.5, path, refined_goal,
goal_lane_id);
refined_path.header.frame_id = "map";
refined_path.header.stamp = this->now();
Expand Down
7 changes: 7 additions & 0 deletions planning/behavior_path_planner/src/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1098,7 +1098,14 @@ bool setGoal(

const Pose refineGoal(const Pose & goal, const lanelet::ConstLanelet & goal_lanelet)
{
// return goal;
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(goal.position);
const double distance = boost::geometry::distance(
goal_lanelet.polygon2d().basicPolygon(), lanelet::utils::to2D(lanelet_point).basicPoint());
if (distance < std::numeric_limits<double>::epsilon()) {
return goal;
}

const auto segment = lanelet::utils::getClosestSegment(
lanelet::utils::to2D(lanelet_point), goal_lanelet.centerline());
if (segment.empty()) {
Expand Down