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(map_based_prediction): consider only routable neighbours for lane change #5669

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
Expand Up @@ -29,5 +29,6 @@
diff_dist_threshold_to_left_bound: 0.29 #[m]
diff_dist_threshold_to_right_bound: -0.29 #[m]
num_continuous_state_transition: 3
consider_only_routable_neighbours: false

Check warning on line 32 in perception/map_based_prediction/config/map_based_prediction.param.yaml

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (routable)

reference_path_resolution: 0.5 #[m]
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,7 @@ class MapBasedPredictionNode : public rclcpp::Node
double diff_dist_threshold_to_left_bound_;
double diff_dist_threshold_to_right_bound_;
int num_continuous_state_transition_;
bool consider_only_routable_neighbours_;
double reference_path_resolution_;

// Stop watch
Expand Down
30 changes: 18 additions & 12 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1532 to 1536, 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.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.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 6.08 to 6.10, 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 @@ -760,6 +760,9 @@

num_continuous_state_transition_ =
declare_parameter<int>("lane_change_detection.num_continuous_state_transition");

consider_only_routable_neighbours_ =
declare_parameter<bool>("lane_change_detection.consider_only_routable_neighbours");

Check warning on line 765 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L764-L765

Added lines #L764 - L765 were not covered by tests
}
reference_path_resolution_ = declare_parameter<double>("reference_path_resolution");
/* prediction path will disabled when the estimated path length exceeds lanelet length. This
Expand Down Expand Up @@ -1514,19 +1517,22 @@
if (!!opt) {
return *opt;
}
const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft(lanelet)
: routing_graph_ptr_->adjacentRight(lanelet);
if (!!adjacent) {
return *adjacent;
}
// search for unconnected lanelet
const auto unconnected_lanelets = get_left
? getLeftLineSharingLanelets(lanelet, lanelet_map_ptr_)
: getRightLineSharingLanelets(lanelet, lanelet_map_ptr_);
// just return first candidate of unconnected lanelet for now
if (!unconnected_lanelets.empty()) {
return unconnected_lanelets.front();
if (!consider_only_routable_neighbours_) {

Check warning on line 1520 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1520

Added line #L1520 was not covered by tests
const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft(lanelet)
: routing_graph_ptr_->adjacentRight(lanelet);
if (!!adjacent) {

Check warning on line 1523 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1522-L1523

Added lines #L1522 - L1523 were not covered by tests
return *adjacent;
}
// search for unconnected lanelet
const auto unconnected_lanelets =
get_left ? getLeftLineSharingLanelets(lanelet, lanelet_map_ptr_)
: getRightLineSharingLanelets(lanelet, lanelet_map_ptr_);

Check warning on line 1529 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1528-L1529

Added lines #L1528 - L1529 were not covered by tests
// just return first candidate of unconnected lanelet for now
if (!unconnected_lanelets.empty()) {

Check warning on line 1531 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1531

Added line #L1531 was not covered by tests
return unconnected_lanelets.front();
}
}

Check warning on line 1535 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::getPredictedReferencePath increases in cyclomatic complexity from 16 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 1535 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

MapBasedPredictionNode::getPredictedReferencePath has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested 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.
// if no candidate lanelet found, return empty
return std::nullopt;
};
Expand Down
Loading