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

fix(intersection): additional fix for 8520 #8561

Merged
merged 3 commits into from
Aug 21, 2024
Merged
Show file tree
Hide file tree
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
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 12.08 to 12.15, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// 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 @@ -934,25 +934,32 @@
detection_lanelets.push_back(detection_lanelet);
}

std::vector<lanelet::ConstLineString3d> detection_divisions;
if (detection_lanelets.empty()) {
// NOTE(soblin): due to the above filtering detection_lanelets may be empty or do not contain
// conflicting_detection_lanelets
// OK to return empty detction_divsions
return detection_divisions;
}

// (1) tsort detection_lanelets
const auto [merged_detection_lanelets, originals] = util::mergeLaneletsByTopologicalSort(
detection_lanelets, conflicting_detection_lanelets, routing_graph_ptr);

// (2) merge each branch to one lanelet
// NOTE: somehow bg::area() for merged lanelet does not work, so calculate it here
std::vector<std::pair<lanelet::ConstLanelet, double>> merged_lanelet_with_area;
for (unsigned i = 0; i < merged_detection_lanelets.size(); ++i) {
const auto & merged_detection_lanelet = merged_detection_lanelets.at(i);
const auto & original = originals.at(i);
double area = 0;
for (const auto & partition : original) {
area += bg::area(partition.polygon2d().basicPolygon());
}
merged_lanelet_with_area.emplace_back(merged_detection_lanelet, area);
}

// (3) discretize each merged lanelet

Check warning on line 962 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

IntersectionModule::generateDetectionLaneDivisions has a cyclomatic complexity of 9, threshold = 9. 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.
std::vector<lanelet::ConstLineString3d> detection_divisions;
for (const auto & [merged_lanelet, area] : merged_lanelet_with_area) {
const double length = bg::length(merged_lanelet.centerline());
const double width = area / length;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.44 to 4.75, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// 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 @@ -32,10 +32,13 @@

#include <algorithm>
#include <cmath>
#include <limits>
#include <map>
#include <memory>
#include <queue>
#include <set>
#include <string>
#include <unordered_map>
#include <unordered_set>
#include <vector>

namespace autoware::behavior_velocity_planner::util
Expand Down Expand Up @@ -212,42 +215,35 @@
}
return std::nullopt;
}
std::vector<std::vector<size_t>> retrievePathsBackward(
const std::vector<std::vector<bool>> & adjacency, size_t start_node)

void retrievePathsBackward(
const std::vector<std::vector<bool>> & adjacency, const size_t src_ind,
const std::vector<size_t> & visited_inds, std::vector<std::vector<size_t>> & paths)
{
std::vector<std::vector<size_t>> paths;
std::vector<size_t> current_path;
std::unordered_set<size_t> visited;

std::function<void(size_t)> retrieve_paths_backward_impl = [&](size_t src_ind) {
current_path.push_back(src_ind);
visited.insert(src_ind);

bool is_terminal = true;
const auto & nexts = adjacency[src_ind];

for (size_t next = 0; next < nexts.size(); ++next) {
if (nexts[next]) {
is_terminal = false;
if (visited.find(next) == visited.end()) {
retrieve_paths_backward_impl(next);
} else {
// Loop detected
paths.push_back(current_path);
}
}
const auto & nexts = adjacency.at(src_ind);
const bool is_terminal = (std::find(nexts.begin(), nexts.end(), true) == nexts.end());
if (is_terminal) {
std::vector<size_t> path(visited_inds.begin(), visited_inds.end());
path.push_back(src_ind);
paths.emplace_back(std::move(path));
return;
}
for (size_t next = 0; next < nexts.size(); next++) {
if (!nexts.at(next)) {
continue;
}

if (is_terminal) {
paths.push_back(current_path);
if (std::find(visited_inds.begin(), visited_inds.end(), next) != visited_inds.end()) {
// loop detected
std::vector<size_t> path(visited_inds.begin(), visited_inds.end());
path.push_back(src_ind);
paths.emplace_back(std::move(path));
continue;
}

current_path.pop_back();
visited.erase(src_ind);
};

retrieve_paths_backward_impl(start_node);
return paths;
auto new_visited_inds = visited_inds;
new_visited_inds.push_back(src_ind);
retrievePathsBackward(adjacency, next, new_visited_inds, paths);
}
return;
}

std::pair<lanelet::ConstLanelets, std::vector<lanelet::ConstLanelets>>
Expand All @@ -269,48 +265,61 @@
}
std::set<size_t> terminal_inds;
for (const auto & terminal_lanelet : terminal_lanelets) {
terminal_inds.insert(Id2ind[terminal_lanelet.id()]);
if (Id2ind.count(terminal_lanelet.id()) > 0) {
terminal_inds.insert(Id2ind[terminal_lanelet.id()]);
}
}

// create adjacency matrix
const auto n_node = lanelets.size();
std::vector<std::vector<bool>> adjacency(n_node, std::vector<bool>(n_node, false));

std::vector<std::vector<bool>> adjacency(n_node);
for (size_t dst = 0; dst < n_node; ++dst) {
adjacency[dst].resize(n_node);
for (size_t src = 0; src < n_node; ++src) {
adjacency[dst][src] = false;
}
}
// NOTE: this function aims to traverse the detection lanelet in the lane direction, so if lane B
// follows lane A on the routing_graph, adj[A][B] = true
for (const auto & lanelet : lanelets) {
const auto & followings = routing_graph_ptr->following(lanelet);
const auto src = lanelet.id();
for (const auto & following : followings) {
if (const auto dst = following.id(); lanelet_Ids.find(dst) != lanelet_Ids.end()) {
adjacency[(Id2ind[dst])][(Id2ind[src])] = true;
}
}
}

std::unordered_map<size_t, std::vector<std::vector<size_t>>> branches;
for (const auto & terminal_ind : terminal_inds) {
branches[terminal_ind] = retrievePathsBackward(adjacency, terminal_ind);
std::vector<std::vector<size_t>> paths;
std::vector<size_t> visited;
retrievePathsBackward(adjacency, terminal_ind, visited, paths);
branches[terminal_ind] = std::move(paths);

Check warning on line 299 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp#L299

Added line #L299 was not covered by tests
}

for (auto & [terminal_ind, paths] : branches) {
for (auto it = branches.begin(); it != branches.end(); it++) {
auto & paths = it->second;
for (auto & path : paths) {
std::reverse(path.begin(), path.end());
}
}
lanelet::ConstLanelets merged;
std::vector<lanelet::ConstLanelets> originals;
for (const auto & [ind, sub_branches] : branches) {
if (sub_branches.empty()) {
if (sub_branches.size() == 0) {
continue;
}
for (const auto & sub_inds : sub_branches) {
lanelet::ConstLanelets to_merge;
lanelet::ConstLanelets to_be_merged;
originals.push_back(lanelet::ConstLanelets({}));
auto & original = originals.back();
for (const auto & sub_ind : sub_inds) {
to_merge.push_back(Id2lanelet[ind2Id[sub_ind]]);
to_be_merged.push_back(Id2lanelet[ind2Id[sub_ind]]);
original.push_back(Id2lanelet[ind2Id[sub_ind]]);
}
originals.push_back(to_merge);
merged.push_back(lanelet::utils::combineLaneletsShape(to_merge));
merged.push_back(lanelet::utils::combineLaneletsShape(to_be_merged));

Check warning on line 322 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

mergeLaneletsByTopologicalSort increases in cyclomatic complexity from 14 to 17, threshold = 9. 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.

Check warning on line 322 in planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Bumpy Road Ahead

mergeLaneletsByTopologicalSort increases from 4 to 6 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.
}
}
return {merged, originals};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,34 +110,22 @@ geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection(
* @brief this function sorts the set of lanelets topologically using topological sort and merges
* the lanelets from each root to each end. each branch is merged and returned with the original
* lanelets
*
* @param lanelets The set of input lanelets to be processed
* @param terminal_lanelets The set of lanelets considered as terminal
* @param routing_graph_ptr Pointer to the routing graph used for determining lanelet
* connections
*
* @return A pair containing:
* - First: A vector of merged lanelets, where each element represents a merged lanelet from
* a branch
* - Second: A vector of vectors, where each inner vector contains the original lanelets
* that were merged to form the corresponding merged lanelet
* @param[in] lanelets the set of lanelets
* @param[in] routing_graph_ptr the routing graph
* @return the pair of merged lanelets and their corresponding original lanelets
*/
std::pair<lanelet::ConstLanelets, std::vector<lanelet::ConstLanelets>>
mergeLaneletsByTopologicalSort(
const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & terminal_lanelets,
const lanelet::routing::RoutingGraphPtr routing_graph_ptr);

/**
* @brief Retrieves all paths from the given source to terminal nodes on the tree
*
* @param adjacency A 2D vector representing the adjacency matrix of the graph
* @param src_ind The index of the current source node being processed
*
* @return A vector of vectors, where each inner vector represents a path from the source node to a
* terminal node.
* @brief this functions retrieves all the paths from the given source to terminal nodes on the tree
@param[in] visited_inds visited node indices excluding src_ind so far
*/
std::vector<std::vector<size_t>> retrievePathsBackward(
const std::vector<std::vector<bool>> & adjacency, size_t start_node);
void retrievePathsBackward(
const std::vector<std::vector<bool>> & adjacency, const size_t src_ind,
const std::vector<size_t> & visited_inds, std::vector<std::vector<size_t>> & paths);

/**
* @brief find the index of the first point where vehicle footprint intersects with the given
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,16 +42,16 @@ TEST(TestUtil, retrievePathsBackward)
};
{
const size_t src_ind = 6;
auto paths =
autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind);
std::vector<std::vector<size_t>> paths;
autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind, {}, paths);
EXPECT_EQ(paths.size(), 1);
EXPECT_EQ(paths.at(0).size(), 1);
EXPECT_EQ(paths.at(0).at(0), 6);
}
{
const size_t src_ind = 4;
auto paths =
autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind);
std::vector<std::vector<size_t>> paths;
autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind, {}, paths);
EXPECT_EQ(paths.size(), 2);
// 4 --> 6
EXPECT_EQ(paths.at(0).size(), 2);
Expand All @@ -64,8 +64,8 @@ TEST(TestUtil, retrievePathsBackward)
}
{
const size_t src_ind = 0;
auto paths =
autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind);
std::vector<std::vector<size_t>> paths;
autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind, {}, paths);
EXPECT_EQ(paths.size(), 3);
// 0 --> 1 --> 2 --> 4 --> 6
EXPECT_EQ(paths.at(0).size(), 5);
Expand Down
Loading