@@ -2141,13 +2141,17 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
2141
2141
2142
2142
// Find lanelets for goal point.
2143
2143
lanelet::ConstLanelet goal_lanelet;
2144
- if (!lanelet::utils::query::getClosestLanelet (road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2145
- RCLCPP_WARN_STREAM (
2146
- logger_, " Failed to find closest lanelet."
2147
- << std::endl
2148
- << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2149
- << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl);
2150
- return false ;
2144
+ lanelet::ConstLanelets goal_lanelets;
2145
+ if (!lanelet::utils::query::getCurrentLanelets (road_lanelets_, goal_checkpoint, &goal_lanelets)) {
2146
+ if (!lanelet::utils::query::getClosestLanelet (road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2147
+ RCLCPP_WARN_STREAM (
2148
+ logger_, " Failed to find current lanelet."
2149
+ << std::endl
2150
+ << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2151
+ << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl);
2152
+ return false ;
2153
+ }
2154
+ goal_lanelets = {goal_lanelet};
2151
2155
}
2152
2156
2153
2157
lanelet::Optional<lanelet::routing::Route> optional_route;
@@ -2159,24 +2163,39 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
2159
2163
constexpr double yaw_threshold = M_PI / 2.0 ;
2160
2164
2161
2165
for (const auto & st_llt : start_lanelets) {
2162
- // check if the angle difference between start_checkpoint and start lanelet center line
2163
- // orientation is in yaw_threshold range
2164
- double lanelet_angle = lanelet::utils::getLaneletAngle (st_llt, start_checkpoint.position );
2165
- double pose_yaw = tf2::getYaw (start_checkpoint.orientation );
2166
- double angle_diff = std::abs (autoware_utils::normalize_radian (lanelet_angle - pose_yaw));
2167
-
2168
- bool is_proper_angle = angle_diff <= std::abs (yaw_threshold);
2169
-
2170
- optional_route = routing_graph_ptr_->getRoute (st_llt, goal_lanelet, 0 );
2171
- if (!optional_route || !is_proper_angle) {
2172
- RCLCPP_ERROR_STREAM (
2173
- logger_, " Failed to find a proper route!"
2174
- << std::endl
2175
- << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2176
- << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl
2177
- << " - start lane id: " << st_llt.id () << std::endl
2178
- << " - goal lane id: " << goal_lanelet.id () << std::endl);
2179
- continue ;
2166
+ for (const auto & gl_llt : goal_lanelets) {
2167
+ // check if the angle difference between start_checkpoint and start lanelet center line
2168
+ // orientation is in yaw_threshold range
2169
+ double yaw_threshold = M_PI / 2.0 ;
2170
+ bool is_proper_angle = false ;
2171
+ {
2172
+ double lanelet_angle = lanelet::utils::getLaneletAngle (st_llt, start_checkpoint.position );
2173
+ double pose_yaw = tf2::getYaw (start_checkpoint.orientation );
2174
+ double angle_diff = std::abs (autoware_utils::normalize_radian (lanelet_angle - pose_yaw));
2175
+
2176
+ if (angle_diff <= std::abs (yaw_threshold)) {
2177
+ is_proper_angle = true ;
2178
+ }
2179
+ }
2180
+
2181
+ optional_route = routing_graph_ptr_->getRoute (st_llt, gl_llt, 0 );
2182
+ if (!optional_route || !is_proper_angle) {
2183
+ RCLCPP_ERROR_STREAM (
2184
+ logger_, " Failed to find a proper route!"
2185
+ << std::endl
2186
+ << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2187
+ << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl
2188
+ << " - start lane id: " << st_llt.id () << std::endl
2189
+ << " - goal lane id: " << gl_llt.id () << std::endl);
2190
+ } else {
2191
+ is_route_found = true ;
2192
+ if (optional_route->length2d () < shortest_path_length2d) {
2193
+ shortest_path_length2d = optional_route->length2d ();
2194
+ shortest_path = optional_route->shortestPath ();
2195
+ start_lanelet = st_llt;
2196
+ goal_lanelet = gl_llt;
2197
+ }
2198
+ }
2180
2199
}
2181
2200
is_route_found = true ;
2182
2201
if (angle_diff < smallest_angle_diff) {
0 commit comments