Skip to content

Commit a54b73e

Browse files
authored
fix(probabilistic_occupancy_grid_map): fix knownConditionTrueFalse warning (#7619)
Signed-off-by: Ryuta Kambe <ryuta.kambe@tier4.jp>
1 parent 3900cbe commit a54b73e

File tree

1 file changed

+3
-10
lines changed

1 file changed

+3
-10
lines changed

perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp

+3-10
Original file line numberDiff line numberDiff line change
@@ -225,11 +225,9 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
225225

226226
if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) {
227227
const auto & source = obstacle_pointcloud_angle_bin.at(dist_index);
228-
if (!no_visible_point_beyond) {
229-
raytrace(
230-
source.wx, source.wy, source.projected_wx, source.projected_wy,
231-
occupancy_cost_value::NO_INFORMATION);
232-
}
228+
raytrace(
229+
source.wx, source.wy, source.projected_wx, source.projected_wy,
230+
occupancy_cost_value::NO_INFORMATION);
233231
continue;
234232
}
235233

@@ -238,11 +236,6 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud(
238236
obstacle_pointcloud_angle_bin.at(dist_index).range);
239237
if (next_obstacle_point_distance <= obstacle_separation_threshold_) {
240238
continue;
241-
} else if (no_visible_point_beyond) {
242-
const auto & source = obstacle_pointcloud_angle_bin.at(dist_index);
243-
const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1);
244-
raytrace(source.wx, source.wy, target.wx, target.wy, occupancy_cost_value::NO_INFORMATION);
245-
continue;
246239
}
247240

248241
auto next_raw_distance =

0 commit comments

Comments
 (0)