@@ -2114,13 +2114,17 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
2114
2114
2115
2115
// Find lanelets for goal point.
2116
2116
lanelet::ConstLanelet goal_lanelet;
2117
- if (!lanelet::utils::query::getClosestLanelet (road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2118
- RCLCPP_WARN_STREAM (
2119
- logger_, " Failed to find closest lanelet."
2120
- << std::endl
2121
- << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2122
- << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl);
2123
- return false ;
2117
+ lanelet::ConstLanelets goal_lanelets;
2118
+ if (!lanelet::utils::query::getCurrentLanelets (road_lanelets_, goal_checkpoint, &goal_lanelets)) {
2119
+ if (!lanelet::utils::query::getClosestLanelet (road_lanelets_, goal_checkpoint, &goal_lanelet)) {
2120
+ RCLCPP_WARN_STREAM (
2121
+ logger_, " Failed to find current lanelet."
2122
+ << std::endl
2123
+ << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2124
+ << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl);
2125
+ return false ;
2126
+ }
2127
+ goal_lanelets = {goal_lanelet};
2124
2128
}
2125
2129
2126
2130
lanelet::Optional<lanelet::routing::Route> optional_route;
@@ -2133,36 +2137,38 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
2133
2137
double shortest_path_length2d = std::numeric_limits<double >::max ();
2134
2138
2135
2139
for (const auto & st_llt : start_lanelets) {
2136
- // check if the angle difference between start_checkpoint and start lanelet center line
2137
- // orientation is in yaw_threshold range
2138
- double yaw_threshold = M_PI / 2.0 ;
2139
- bool is_proper_angle = false ;
2140
- {
2141
- double lanelet_angle = lanelet::utils::getLaneletAngle (st_llt, start_checkpoint.position );
2142
- double pose_yaw = tf2::getYaw (start_checkpoint.orientation );
2143
- double angle_diff = std::abs (autoware_utils::normalize_radian (lanelet_angle - pose_yaw));
2144
-
2145
- if (angle_diff <= std::abs (yaw_threshold)) {
2146
- is_proper_angle = true ;
2140
+ for (const auto & gl_llt : goal_lanelets) {
2141
+ // check if the angle difference between start_checkpoint and start lanelet center line
2142
+ // orientation is in yaw_threshold range
2143
+ double yaw_threshold = M_PI / 2.0 ;
2144
+ bool is_proper_angle = false ;
2145
+ {
2146
+ double lanelet_angle = lanelet::utils::getLaneletAngle (st_llt, start_checkpoint.position );
2147
+ double pose_yaw = tf2::getYaw (start_checkpoint.orientation );
2148
+ double angle_diff = std::abs (autoware_utils::normalize_radian (lanelet_angle - pose_yaw));
2149
+
2150
+ if (angle_diff <= std::abs (yaw_threshold)) {
2151
+ is_proper_angle = true ;
2152
+ }
2147
2153
}
2148
- }
2149
-
2150
- optional_route = routing_graph_ptr_->getRoute (st_llt, goal_lanelet, 0 );
2151
- if (!optional_route || !is_proper_angle) {
2152
- RCLCPP_ERROR_STREAM (
2153
- logger_, " Failed to find a proper route!"
2154
- << std::endl
2155
- << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2156
- << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl
2157
- << " - start lane id: " << st_llt.id () << std::endl
2158
- << " - goal lane id: " << goal_lanelet.id () << std::endl);
2159
- } else {
2160
- is_route_found = true ;
2161
2154
2162
- if (optional_route->length2d () < shortest_path_length2d) {
2163
- shortest_path_length2d = optional_route->length2d ();
2164
- shortest_path = optional_route->shortestPath ();
2165
- start_lanelet = st_llt;
2155
+ optional_route = routing_graph_ptr_->getRoute (st_llt, gl_llt, 0 );
2156
+ if (!optional_route || !is_proper_angle) {
2157
+ RCLCPP_ERROR_STREAM (
2158
+ logger_, " Failed to find a proper route!"
2159
+ << std::endl
2160
+ << " - start checkpoint: " << toString (start_checkpoint) << std::endl
2161
+ << " - goal checkpoint: " << toString (goal_checkpoint) << std::endl
2162
+ << " - start lane id: " << st_llt.id () << std::endl
2163
+ << " - goal lane id: " << gl_llt.id () << std::endl);
2164
+ } else {
2165
+ is_route_found = true ;
2166
+ if (optional_route->length2d () < shortest_path_length2d) {
2167
+ shortest_path_length2d = optional_route->length2d ();
2168
+ shortest_path = optional_route->shortestPath ();
2169
+ start_lanelet = st_llt;
2170
+ goal_lanelet = gl_llt;
2171
+ }
2166
2172
}
2167
2173
}
2168
2174
}
0 commit comments