diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp index 01fc4b182e211..8b48d1a867126 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp @@ -192,9 +192,11 @@ bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_h const auto shoulder_lanes = route_handler->getShoulderLanelets(); lanelet::ConstLanelet closest_shoulder_lane{}; - lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &closest_shoulder_lane); + if (lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &closest_shoulder_lane)) { + return lanelet::utils::isInLanelet(goal_pose, closest_shoulder_lane, 0.1); + } - return lanelet::utils::isInLanelet(goal_pose, closest_shoulder_lane, 0.1); + return false; } } // namespace goal_planner_utils