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

refactor(behavior_velocity_occlusion_spot_module): reduce cppcheck warning #6987

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 @@ -118,7 +118,7 @@ MarkerArray makeDebugInfoMarkers(T & debug_data)
{
// add slow down markers for occlusion spot
MarkerArray debug_markers;
auto & possible_collisions = debug_data.possible_collisions;
const auto & possible_collisions = debug_data.possible_collisions;
size_t id = 0;
// draw obstacle collision
for (const auto & pc : possible_collisions) {
Expand Down
66 changes: 16 additions & 50 deletions planning/behavior_velocity_occlusion_spot_module/src/grid_utils.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 planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 4.36 to 4.08, 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 @@ -43,23 +43,6 @@
return line_poly;
}

std::vector<std::pair<grid_map::Position, grid_map::Position>> pointsToRays(
const grid_map::Position p0, const grid_map::Position p1, const double radius)
{
using grid_map::Position;
std::vector<std::pair<Position, Position>> lines;
const double angle = atan2(p0.y() - p1.y(), p0.x() - p1.x());
const double r = radius;
lines.emplace_back(std::make_pair(p0, p1));
lines.emplace_back(std::make_pair(
Position(p0.x() + r * sin(angle), p0.y() - r * cos(angle)),
Position(p1.x() + r * sin(angle), p1.y() - r * cos(angle))));
lines.emplace_back(std::make_pair(
Position(p1.x() - r * sin(angle), p1.y() + r * cos(angle)),
Position(p0.x() - r * sin(angle), p0.y() + r * cos(angle))));
return lines;
}

void findOcclusionSpots(
std::vector<grid_map::Position> & occlusion_spot_positions, const grid_map::GridMap & grid,
const Polygon2d & polygon, [[maybe_unused]] double min_size)
Expand All @@ -85,37 +68,22 @@
const grid_map::GridMap & grid, const grid_map::Position & p1, const grid_map::Position & p2,
const double radius)
{
const grid_map::Matrix & grid_data = grid["layer"];
bool polys = true;
try {
if (polys) {
Point2d occlusion_p = {p1.x(), p1.y()};
Point2d collision_p = {p2.x(), p2.y()};
Polygon2d polygon = pointsToPoly(occlusion_p, collision_p, radius);
grid_map::Polygon grid_polygon;
for (const auto & point : polygon.outer()) {
grid_polygon.addVertex({point.x(), point.y()});
}
for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd();
++iterator) {
const grid_map::Index & index = *iterator;
if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) {
return false;
}
}
} else {
std::vector<std::pair<grid_map::Position, grid_map::Position>> lines =
pointsToRays(p1, p2, radius);
for (const auto & p : lines) {
for (grid_map::LineIterator iterator(grid, p.first, p.second); !iterator.isPastEnd();
++iterator) {
const grid_map::Index & index = *iterator;
if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) {
return false;
}
}
Point2d occlusion_p = {p1.x(), p1.y()};
Point2d collision_p = {p2.x(), p2.y()};
Polygon2d polygon = pointsToPoly(occlusion_p, collision_p, radius);
grid_map::Polygon grid_polygon;
for (const auto & point : polygon.outer()) {
grid_polygon.addVertex({point.x(), point.y()});
}
for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd();
++iterator) {
const grid_map::Index & index = *iterator;
if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) {
return false;
}
} // polys or not
}

Check notice on line 86 in planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

isCollisionFree is no longer above the threshold for cyclomatic complexity. 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 86 in planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

isCollisionFree is no longer above the threshold for logical blocks with deeply nested code. 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.

Check notice on line 86 in planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Deep, Nested Complexity

isCollisionFree is no longer above the threshold for nested complexity depth
} catch (const std::invalid_argument & e) {
std::cerr << e.what() << std::endl;
return false;
Expand Down Expand Up @@ -324,7 +292,7 @@
const int idx = (height - 1 - y) + (width - 1 - x) * height;
unsigned char intensity = cv_image.at<unsigned char>(y, x);
if (intensity == grid_utils::occlusion_cost_value::FREE_SPACE) {
intensity = grid_utils::occlusion_cost_value::FREE_SPACE;
// do nothing
} else if (intensity == grid_utils::occlusion_cost_value::UNKNOWN_IMAGE) {
intensity = grid_utils::occlusion_cost_value::UNKNOWN;
} else if (intensity == grid_utils::occlusion_cost_value::OCCUPIED_IMAGE) {
Expand All @@ -348,14 +316,12 @@
unsigned char intensity = occupancy_grid.data.at(idx);
if (intensity <= param.free_space_max) {
continue;
} else if (param.free_space_max < intensity && intensity < param.occupied_min) {
} else if (intensity < param.occupied_min) {
intensity = grid_utils::occlusion_cost_value::UNKNOWN_IMAGE;
occlusion_image->at<unsigned char>(y, x) = intensity;
} else if (param.occupied_min <= intensity) {
} else {
intensity = grid_utils::occlusion_cost_value::OCCUPIED_IMAGE;
border_image->at<unsigned char>(y, x) = intensity;

Check notice on line 324 in planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

toQuantizedImage is no longer above the threshold for cyclomatic complexity. 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.
} else {
throw std::logic_error("behavior_velocity[occlusion_spot_grid]: invalid if clause");
}
}
}
Expand Down
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 planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.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.05 to 4.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 @@ -117,6 +117,9 @@
size_t collision_index = 0;
double dist_along_path_point = offset;
double dist_along_next_path_point = dist_along_path_point;
if (path.points.size() == 0) {
return;
}

Check warning on line 122 in planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

calcSlowDownPointsForPossibleCollision increases in cyclomatic complexity from 9 to 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.
for (size_t idx = closest_idx; idx < path.points.size() - 1; idx++) {
auto p_prev = path.points.at(idx).point;
auto p_next = path.points.at(idx + 1).point;
Expand Down Expand Up @@ -426,7 +429,8 @@
std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
const grid_map::GridMap & grid, const std::vector<grid_map::Position> & occlusion_spot_positions,
const double offset_from_start_to_ego, const Point2d base_point,
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data)
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param,
const DebugData & debug_data)
{
const double baselink_to_front = param.baselink_to_front;
const double right_overhang = param.right_overhang;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,8 @@ void calcSlowDownPointsForPossibleCollision(
std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
const grid_map::GridMap & grid, const std::vector<grid_map::Position> & occlusion_spot_positions,
const double offset_from_start_to_ego, const Point2d base_point,
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data);
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param,
const DebugData & debug_data);
//!< @brief generate possible collisions coming from occlusion spots on the side of the path
bool generatePossibleCollisionsFromGridMap(
std::vector<PossibleCollisionInfo> & possible_collisions, const grid_map::GridMap & grid,
Expand Down
Loading