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

chore(lanelet2_map_loader): enrich error message #6245

Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@
// load map from file
const auto map = load_map(lanelet2_filename, *msg);
if (!map) {
RCLCPP_ERROR(get_logger(), "Failed to load lanelet2_map. Not published.");
return;
}

Expand All @@ -87,6 +88,7 @@
pub_map_bin_ =
create_publisher<HADMapBin>("output/lanelet2_map", rclcpp::QoS{1}.transient_local());
pub_map_bin_->publish(map_bin_msg);
RCLCPP_INFO(get_logger(), "Succeeded to load lanelet2_map. Map is published.");
}

lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
Expand All @@ -105,6 +107,12 @@
const lanelet::projection::LocalProjector projector;
const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors);

if (!errors.empty()) {
for (const auto & error : errors) {
RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error);
}
}

Check warning on line 115 in map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

Lanelet2MapLoaderNode::load_map has a cyclomatic complexity of 10, 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 notice on line 115 in map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

Lanelet2MapLoaderNode::load_map increases from 2 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.
// overwrite local_x, local_y
for (lanelet::Point3d point : map->pointLayer) {
if (point.hasAttribute("local_x")) {
Expand Down
Loading