Skip to content

Commit a7314b6

Browse files
authored
fix(autoware_behavior_path_planner_common): fix bugprone-errors (#9700)
fix: bugprone-error Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>
1 parent 857aa71 commit a7314b6

File tree

2 files changed

+5
-7
lines changed

2 files changed

+5
-7
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -1127,9 +1127,7 @@ std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings(
11271127
get_corresponding_polygon_index(*current_polygon, bound_point.id()));
11281128
}
11291129
} else {
1130-
if (!polygon) {
1131-
will_close_polygon = true;
1132-
} else if (polygon.value().id() != current_polygon.value().id()) {
1130+
if (!polygon || polygon.value().id() != current_polygon.value().id()) {
11331131
will_close_polygon = true;
11341132
} else {
11351133
current_polygon_border_indices.push_back(
@@ -1496,9 +1494,9 @@ std::vector<geometry_msgs::msg::Point> postProcess(
14961494
[](const lanelet::ConstLineString3d & points, std::vector<geometry_msgs::msg::Point> & bound) {
14971495
for (const auto & bound_p : points) {
14981496
const auto cp = lanelet::utils::conversion::toGeomMsgPt(bound_p);
1499-
if (bound.empty()) {
1500-
bound.push_back(cp);
1501-
} else if (autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) {
1497+
if (
1498+
bound.empty() ||
1499+
autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) {
15021500
bound.push_back(cp);
15031501
}
15041502
}

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyG
8080
for (uint32_t i = 0; i < height; i++) {
8181
is_obstacle_table.at(i).resize(width);
8282
for (uint32_t j = 0; j < width; j++) {
83-
const int cost = costmap_.data[i * width + j];
83+
const int cost = costmap_.data[i * width + j]; // NOLINT
8484

8585
if (cost < 0 || param_.obstacle_threshold <= cost) {
8686
is_obstacle_table[i][j] = true;

0 commit comments

Comments
 (0)