From a7314b681a014289818a42c04597c89a149f7bd1 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 20 Dec 2024 17:26:42 +0900 Subject: [PATCH] fix(autoware_behavior_path_planner_common): fix bugprone-errors (#9700) fix: bugprone-error Signed-off-by: kobayu858 --- .../drivable_area_expansion/static_drivable_area.cpp | 10 ++++------ .../occupancy_grid_based_collision_detector.cpp | 2 +- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 0768c620dd054..3b272fd8c6722 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -1127,9 +1127,7 @@ std::vector getBoundWithHatchedRoadMarkings( get_corresponding_polygon_index(*current_polygon, bound_point.id())); } } else { - if (!polygon) { - will_close_polygon = true; - } else if (polygon.value().id() != current_polygon.value().id()) { + if (!polygon || polygon.value().id() != current_polygon.value().id()) { will_close_polygon = true; } else { current_polygon_border_indices.push_back( @@ -1496,9 +1494,9 @@ std::vector postProcess( [](const lanelet::ConstLineString3d & points, std::vector & bound) { for (const auto & bound_p : points) { const auto cp = lanelet::utils::conversion::toGeomMsgPt(bound_p); - if (bound.empty()) { - bound.push_back(cp); - } else if (autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { + if ( + bound.empty() || + autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { bound.push_back(cp); } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp index e65c67065bc54..33f46420ad537 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp @@ -80,7 +80,7 @@ void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyG for (uint32_t i = 0; i < height; i++) { is_obstacle_table.at(i).resize(width); for (uint32_t j = 0; j < width; j++) { - const int cost = costmap_.data[i * width + j]; + const int cost = costmap_.data[i * width + j]; // NOLINT if (cost < 0 || param_.obstacle_threshold <= cost) { is_obstacle_table[i][j] = true;