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(mission_planner): set goal in shoulder lane #2548

Merged
merged 2 commits into from
Dec 22, 2022
Merged
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
38 changes: 19 additions & 19 deletions planning/mission_planner/src/lanelet2_plugins/default_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,6 +272,25 @@ bool DefaultPlanner::is_goal_valid(
const geometry_msgs::msg::Pose & goal, lanelet::ConstLanelets path_lanelets)
{
const auto logger = node_->get_logger();

const auto goal_lanelet_pt = lanelet::utils::conversion::toLaneletPoint(goal.position);

// check if goal is in shoulder lanelet
lanelet::Lanelet closest_shoulder_lanelet;
if (lanelet::utils::query::getClosestLanelet(
shoulder_lanelets_, goal, &closest_shoulder_lanelet)) {
if (is_in_lane(closest_shoulder_lanelet, goal_lanelet_pt)) {
const auto lane_yaw =
lanelet::utils::getLaneletAngle(closest_shoulder_lanelet, goal.position);
const auto goal_yaw = tf2::getYaw(goal.orientation);
const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw);
const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg);
if (std::abs(angle_diff) < th_angle) {
return true;
}
}
}

lanelet::Lanelet closest_lanelet;
if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &closest_lanelet)) {
return false;
Expand All @@ -298,8 +317,6 @@ bool DefaultPlanner::is_goal_valid(
return false;
}

const auto goal_lanelet_pt = lanelet::utils::conversion::toLaneletPoint(goal.position);

if (is_in_lane(closest_lanelet, goal_lanelet_pt)) {
const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet, goal.position);
const auto goal_yaw = tf2::getYaw(goal.orientation);
Expand All @@ -323,23 +340,6 @@ bool DefaultPlanner::is_goal_valid(
return true;
}

// check if goal is in shoulder lanelet
lanelet::Lanelet closest_shoulder_lanelet;
if (!lanelet::utils::query::getClosestLanelet(
shoulder_lanelets_, goal, &closest_shoulder_lanelet)) {
return false;
}
// check if goal pose is in shoulder lane
if (is_in_lane(closest_shoulder_lanelet, goal_lanelet_pt)) {
const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_shoulder_lanelet, goal.position);
const auto goal_yaw = tf2::getYaw(goal.orientation);
const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw);

const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg);
if (std::abs(angle_diff) < th_angle) {
return true;
}
}
return false;
}

Expand Down