Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(route_handler): use start pose yaw and not lanelet length to select start lanelet #6550

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
55 changes: 21 additions & 34 deletions planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021-2023 Tier IV, Inc.

Check notice on line 1 in planning/route_handler/src/route_handler.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1911 to 1900, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -2133,62 +2133,49 @@
lanelet::routing::LaneletPath shortest_path;
bool is_route_found = false;

lanelet::routing::LaneletPath drivable_lane_path;
bool drivable_lane_path_found = false;
double shortest_path_length2d = std::numeric_limits<double>::max();
double smallest_angle_diff = std::numeric_limits<double>::max();
constexpr double yaw_threshold = M_PI / 2.0;

for (const auto & st_llt : start_lanelets) {
// check if the angle difference between start_checkpoint and start lanelet center line
// orientation is in yaw_threshold range
double yaw_threshold = M_PI / 2.0;
bool is_proper_angle = false;
{
double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position);
double pose_yaw = tf2::getYaw(start_checkpoint.orientation);
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));

if (angle_diff <= std::abs(yaw_threshold)) {
is_proper_angle = true;
}
}
double lanelet_angle = lanelet::utils::getLaneletAngle(st_llt, start_checkpoint.position);
double pose_yaw = tf2::getYaw(start_checkpoint.orientation);
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));

bool is_proper_angle = angle_diff <= std::abs(yaw_threshold);

optional_route = routing_graph_ptr_->getRoute(st_llt, goal_lanelet, 0);
if (!optional_route || !is_proper_angle) {
RCLCPP_ERROR_STREAM(
logger_, "Failed to find a proper route!"
<< std::endl
<< " - start checkpoint: " << toString(start_checkpoint) << std::endl
<< " - goal checkpoint: " << toString(goal_checkpoint) << std::endl
<< " - start lane id: " << st_llt.id() << std::endl
<< " - goal lane id: " << goal_lanelet.id() << std::endl);
} else {
is_route_found = true;

if (optional_route->length2d() < shortest_path_length2d) {
shortest_path_length2d = optional_route->length2d();
shortest_path = optional_route->shortestPath();
start_lanelet = st_llt;
}
continue;
}

Check warning on line 2158 in planning/route_handler/src/route_handler.cpp

View check run for this annotation

Codecov / codecov/patch

planning/route_handler/src/route_handler.cpp#L2157-L2158

Added lines #L2157 - L2158 were not covered by tests
is_route_found = true;
if (angle_diff < smallest_angle_diff) {
smallest_angle_diff = angle_diff;
shortest_path = optional_route->shortestPath();
start_lanelet = st_llt;
}
}

if (is_route_found) {
lanelet::routing::LaneletPath path;
if (consider_no_drivable_lanes) {
bool shortest_path_has_no_drivable_lane = hasNoDrivableLaneInPath(shortest_path);
if (shortest_path_has_no_drivable_lane) {
path = [&]() -> lanelet::routing::LaneletPath {
if (!consider_no_drivable_lanes) return shortest_path;
lanelet::routing::LaneletPath drivable_lane_path;

Check warning on line 2171 in planning/route_handler/src/route_handler.cpp

View check run for this annotation

Codecov / codecov/patch

planning/route_handler/src/route_handler.cpp#L2171

Added line #L2171 was not covered by tests
bool drivable_lane_path_found = false;
if (hasNoDrivableLaneInPath(shortest_path)) {
drivable_lane_path_found =
findDrivableLanePath(start_lanelet, goal_lanelet, drivable_lane_path);
}

if (drivable_lane_path_found) {
path = drivable_lane_path;
} else {
path = shortest_path;
}
} else {
path = shortest_path;
}
return (drivable_lane_path_found) ? drivable_lane_path : shortest_path;
}();

Check notice on line 2178 in planning/route_handler/src/route_handler.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Bumpy Road Ahead

RouteHandler::planPathLaneletsBetweenCheckpoints decreases from 4 to 3 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

path_lanelets->reserve(path.size());
for (const auto & llt : path) {
Expand Down
Loading