Skip to content

Commit 7f1702f

Browse files
Ahmed Ebrahimahmeddesokyebrahim
Ahmed Ebrahim
authored andcommitted
feat(remaining_dist_eta): improving and cleaning remaining dist and eta functions
Signed-off-by: AhmedEbrahim <ahmed.ebrahim@leodrive.ai>
1 parent 38e6e07 commit 7f1702f

File tree

1 file changed

+21
-44
lines changed

1 file changed

+21
-44
lines changed

planning/route_handler/src/route_handler.cpp

+21-44
Original file line numberDiff line numberDiff line change
@@ -2261,65 +2261,46 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath &
22612261
}
22622262

22632263
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;
22762267

22772268
lanelet::ConstLanelet current_lanelet;
22782269
getClosestLaneletWithinRoute(current_pose, &current_lanelet);
2270+
2271+
lanelet::ConstLanelet goal_lanelet;
2272+
getGoalLanelet(&goal_lanelet);
22792273

22802274
const lanelet::Optional<lanelet::routing::Route> optional_route =
22812275
routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0);
22822276

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();
22862279

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) {
22962281

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);
22992284
break;
23002285
}
23012286

2302-
if (counter == 0) {
2303-
is_first_time = false;
2304-
tmp_const_lanelets.push_back(llt);
2287+
if (index == 0) {
23052288
lanelet::ArcCoordinates arc_coord =
2306-
lanelet::utils::getArcCoordinates(tmp_const_lanelets, current_pose);
2289+
lanelet::utils::getArcCoordinates({llt}, current_pose);
23072290
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)) {
23112293
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;
23142296
} else {
2315-
length += lanelet::utils::getLaneletLength2d(llt);
2297+
remaining_distance += lanelet::utils::getLaneletLength2d(llt);
23162298
}
23172299

2318-
counter++;
2319-
tmp_const_lanelets.clear();
2300+
index++;
23202301
}
23212302

2322-
return length;
2303+
return remaining_distance;
23232304
}
23242305

23252306
EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(
@@ -2329,18 +2310,14 @@ EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(
23292310
current_vehicle_velocity.x * current_vehicle_velocity.x +
23302311
current_vehicle_velocity.y * current_vehicle_velocity.y);
23312312

2332-
if (remaining_distance < 0.0001 || current_velocity_norm < 0.0001) {
2313+
if (remaining_distance < 0.01 || current_velocity_norm < 0.01) {
23332314
eta.hours = 0;
23342315
eta.minutes = 0;
23352316
eta.seconds = 0;
23362317
return eta;
23372318
}
23382319

23392320
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);
23442321
eta.hours = static_cast<uint8_t>(remaining_time / 3600.0);
23452322
remaining_time = std::fmod(remaining_time, 3600);
23462323
eta.minutes = static_cast<uint8_t>(remaining_time / 60.0);

0 commit comments

Comments
 (0)