@@ -2261,65 +2261,46 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath &
2261
2261
}
2262
2262
2263
2263
double RouteHandler::getRemainingDistance (const Pose & current_pose, const Pose & goal_pose_)
2264
- { /* *
2265
-
2266
- double dist_to_goal = lanelet::geometry::toArcCoordinates(
2267
- lanelet::utils::to2D(lanelet.centerline()),
2268
- lanelet::utils::to2D(target_goal_position).basicPoint())
2269
- .length;
2270
- */
2271
- static bool is_first_time{true };
2272
- double length = 0.0 ;
2273
- size_t counter = 0 ;
2274
- lanelet::ConstLanelet goal_lanelet;
2275
- getGoalLanelet (&goal_lanelet);
2264
+ {
2265
+ double remaining_distance = 0.0 ;
2266
+ size_t index = 0 ;
2276
2267
2277
2268
lanelet::ConstLanelet current_lanelet;
2278
2269
getClosestLaneletWithinRoute (current_pose, ¤t_lanelet);
2270
+
2271
+ lanelet::ConstLanelet goal_lanelet;
2272
+ getGoalLanelet (&goal_lanelet);
2279
2273
2280
2274
const lanelet::Optional<lanelet::routing::Route> optional_route =
2281
2275
routing_graph_ptr_->getRoute (current_lanelet, goal_lanelet, 0 );
2282
2276
2283
- lanelet::routing::LaneletPath shortest_path;
2284
- shortest_path = optional_route->shortestPath ();
2285
- lanelet::ConstLanelets tmp_const_lanelets;
2277
+ lanelet::routing::LaneletPath remaining_shortest_path;
2278
+ remaining_shortest_path = optional_route->shortestPath ();
2286
2279
2287
- for (auto & llt : shortest_path) {
2288
- if (shortest_path.size () == 1 && is_first_time) {
2289
- tmp_const_lanelets.push_back (llt);
2290
- lanelet::ArcCoordinates arc_coord =
2291
- lanelet::utils::getArcCoordinates (tmp_const_lanelets, current_pose);
2292
- double this_lanelet_length = lanelet::utils::getLaneletLength2d (llt);
2293
- length += this_lanelet_length - arc_coord.length ;
2294
- break ;
2295
- }
2280
+ for (auto & llt : remaining_shortest_path) {
2296
2281
2297
- if (shortest_path .size () == 1 && !is_first_time ) {
2298
- length += tier4_autoware_utils::calcDistance2d (current_pose.position , goal_pose_.position );
2282
+ if (remaining_shortest_path .size () == 1 ) {
2283
+ remaining_distance += tier4_autoware_utils::calcDistance2d (current_pose.position , goal_pose_.position );
2299
2284
break ;
2300
2285
}
2301
2286
2302
- if (counter == 0 ) {
2303
- is_first_time = false ;
2304
- tmp_const_lanelets.push_back (llt);
2287
+ if (index == 0 ) {
2305
2288
lanelet::ArcCoordinates arc_coord =
2306
- lanelet::utils::getArcCoordinates (tmp_const_lanelets , current_pose);
2289
+ lanelet::utils::getArcCoordinates ({llt} , current_pose);
2307
2290
double this_lanelet_length = lanelet::utils::getLaneletLength2d (llt);
2308
- length += this_lanelet_length - arc_coord.length ;
2309
- } else if (counter == (shortest_path.size () - 1 )) {
2310
- tmp_const_lanelets.push_back (llt);
2291
+ remaining_distance += this_lanelet_length - arc_coord.length ;
2292
+ } else if (index == (remaining_shortest_path.size () - 1 )) {
2311
2293
lanelet::ArcCoordinates arc_coord =
2312
- lanelet::utils::getArcCoordinates (tmp_const_lanelets , goal_pose_);
2313
- length += arc_coord.length ;
2294
+ lanelet::utils::getArcCoordinates ({llt} , goal_pose_);
2295
+ remaining_distance += arc_coord.length ;
2314
2296
} else {
2315
- length += lanelet::utils::getLaneletLength2d (llt);
2297
+ remaining_distance += lanelet::utils::getLaneletLength2d (llt);
2316
2298
}
2317
2299
2318
- counter++;
2319
- tmp_const_lanelets.clear ();
2300
+ index ++;
2320
2301
}
2321
2302
2322
- return length ;
2303
+ return remaining_distance ;
2323
2304
}
2324
2305
2325
2306
EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival (
@@ -2329,18 +2310,14 @@ EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(
2329
2310
current_vehicle_velocity.x * current_vehicle_velocity.x +
2330
2311
current_vehicle_velocity.y * current_vehicle_velocity.y );
2331
2312
2332
- if (remaining_distance < 0.0001 || current_velocity_norm < 0.0001 ) {
2313
+ if (remaining_distance < 0.01 || current_velocity_norm < 0.01 ) {
2333
2314
eta.hours = 0 ;
2334
2315
eta.minutes = 0 ;
2335
2316
eta.seconds = 0 ;
2336
2317
return eta;
2337
2318
}
2338
2319
2339
2320
double remaining_time = remaining_distance / current_velocity_norm;
2340
- // eta.hours = remaining_time / 3600;
2341
- // remaining_time = std::fmod(remaining_time, 3600);
2342
- // eta.minutes = remaining_time / 60;
2343
- // eta.seconds = fmod(remaining_time, 60);
2344
2321
eta.hours = static_cast <uint8_t >(remaining_time / 3600.0 );
2345
2322
remaining_time = std::fmod (remaining_time, 3600 );
2346
2323
eta.minutes = static_cast <uint8_t >(remaining_time / 60.0 );
0 commit comments