Skip to content

Commit

Permalink
fix(mission_planner): find the first common interval naively for main…
Browse files Browse the repository at this point in the history
…/mrm reroute check

Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Feb 28, 2024
1 parent b86a00d commit 84d7736
Showing 1 changed file with 40 additions and 60 deletions.
100 changes: 40 additions & 60 deletions planning/mission_planner/src/mission_planner/mission_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include <lanelet2_core/geometry/LineString.h>

#include <algorithm>

#include <utility>
namespace mission_planner
{

Expand Down Expand Up @@ -413,80 +413,57 @@ bool MissionPlanner::check_reroute_safety(
return false;
}

bool is_same = false;
for (const auto & primitive : original_primitives) {
const auto has_same = [&](const auto & p) { return p.id == primitive.id; };
is_same = std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
target_primitives.end();
const bool is_same =
std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
target_primitives.end();
if (!is_same) {
return false;
}
}
return is_same;
return true;
};

// find idx of original primitives that matches the target primitives
const auto start_idx_opt = std::invoke([&]() -> std::optional<size_t> {
/*
* find the index of the original route that has same idx with the front segment of the new
* route
*
* start_idx
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* original original original original original
* target target target
*/
const auto target_front_primitives = target_route.segments.front().primitives;
for (size_t i = 0; i < original_route.segments.size(); ++i) {
const auto & original_primitives = original_route.segments.at(i).primitives;
if (hasSamePrimitives(original_primitives, target_front_primitives)) {
return i;
}
}

/*
* find the target route that has same idx with the front segment of the original route
*
* start_idx
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* original original original
* target target target target target
*/
const auto original_front_primitives = original_route.segments.front().primitives;
for (size_t i = 0; i < target_route.segments.size(); ++i) {
const auto & target_primitives = target_route.segments.at(i).primitives;
if (hasSamePrimitives(target_primitives, original_front_primitives)) {
return 0;
// NOTE: the original/target route may share the common segment interval in the middle, not from
// the beginning of either route
const auto start_idx_opt =
std::invoke([&]() -> std::optional<std::pair<size_t /* original */, size_t /* target */>> {
for (size_t i = 0; i < original_route.segments.size(); ++i) {
const auto & original_segment = original_route.segments.at(i).primitives;
for (size_t j = 0; j < target_route.segments.size(); ++j) {
const auto & target_segment = target_route.segments.at(j).primitives;
if (hasSamePrimitives(original_segment, target_segment)) {
return std::make_pair(i, j);
}
}
}
}

return std::nullopt;
});
return std::nullopt;
});
if (!start_idx_opt.has_value()) {
RCLCPP_ERROR(
get_logger(), "Check reroute safety failed. Cannot find the start index of the route.");
return false;
}
const size_t start_idx = start_idx_opt.value();
const auto [start_idx_original, start_idx_target] = start_idx_opt.value();

// find last idx that matches the target primitives
size_t end_idx = start_idx;
for (size_t i = 1; i < target_route.segments.size(); ++i) {
if (start_idx + i > original_route.segments.size() - 1) {
size_t end_idx_original = start_idx_original;
size_t end_idx_target = start_idx_target;
for (size_t i = 1; i < target_route.segments.size() - start_idx_target; ++i) {
if (start_idx_original + i > original_route.segments.size() - 1) {
break;
}

const auto & original_primitives = original_route.segments.at(start_idx + i).primitives;
const auto & target_primitives = target_route.segments.at(i).primitives;
const auto & original_primitives =
original_route.segments.at(start_idx_original + i).primitives;
const auto & target_primitives = target_route.segments.at(start_idx_target + i).primitives;
if (!hasSamePrimitives(original_primitives, target_primitives)) {
break;
}
end_idx = start_idx + i;
end_idx_original = start_idx_original + i;
end_idx_target = start_idx_target + i;
}

// create map
Expand All @@ -495,7 +472,7 @@ bool MissionPlanner::check_reroute_safety(

// compute distance from the current pose to the end of the current lanelet
const auto current_pose = target_route.start_pose;
const auto primitives = original_route.segments.at(start_idx).primitives;
const auto primitives = original_route.segments.at(start_idx_original).primitives;
lanelet::ConstLanelets start_lanelets;
for (const auto & primitive : primitives) {
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
Expand All @@ -518,7 +495,7 @@ bool MissionPlanner::check_reroute_safety(
double accumulated_length = lanelet_length - dist_to_current_pose;

// compute distance from the start_idx+1 to end_idx
for (size_t i = start_idx + 1; i <= end_idx; ++i) {
for (size_t i = start_idx_original + 1; i <= end_idx_original; ++i) {
const auto primitives = original_route.segments.at(i).primitives;
if (primitives.empty()) {
break;
Expand All @@ -534,7 +511,7 @@ bool MissionPlanner::check_reroute_safety(
}

// check if the goal is inside of the target terminal lanelet
const auto & target_end_primitives = target_route.segments.at(end_idx - start_idx).primitives;
const auto & target_end_primitives = target_route.segments.at(end_idx_target).primitives;
const auto & target_goal = target_route.goal_pose;
for (const auto & target_end_primitive : target_end_primitives) {
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(target_end_primitive.id);
Expand All @@ -546,8 +523,11 @@ bool MissionPlanner::check_reroute_safety(
lanelet::utils::to2D(target_goal_position).basicPoint())
.length;
const double target_lanelet_length = lanelet::utils::getLaneletLength2d(lanelet);
const double dist = target_lanelet_length - dist_to_goal;
accumulated_length = std::max(accumulated_length - dist, 0.0);
// NOTE: `accumulated_length` here contains the length of the entire target_end_primitive, so
// the remaining distance from the goal to the end of the target_end_primitive needs to be
// subtracted.
const double remaining_dist = target_lanelet_length - dist_to_goal;
accumulated_length = std::max(accumulated_length - remaining_dist, 0.0);

Check warning on line 530 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MissionPlanner::check_reroute_safety already has high cyclomatic complexity, and now it increases in Lines of Code from 123 to 125. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
break;
}
}
Expand Down

0 comments on commit 84d7736

Please sign in to comment.