@@ -117,8 +117,7 @@ void clear_behind_objects(
117
117
lanelet::geometry::distance2d (grid_map_position, object_position) < range) {
118
118
lanelet::BasicPoints2d edge_points;
119
119
const auto object_polygon = tier4_autoware_utils::toPolygon2d (object);
120
- for (const auto & edge_point : object_polygon.outer ())
121
- edge_points.push_back (edge_point);
120
+ for (const auto & edge_point : object_polygon.outer ()) edge_points.push_back (edge_point);
122
121
std::sort (edge_points.begin (), edge_points.end (), angle_cmp);
123
122
// points.push_back(interpolate_point({object_position, edge_point}, 10.0 * range));
124
123
grid_map::Polygon polygon_to_clear;
@@ -145,7 +144,9 @@ bool is_crosswalk_occluded(
145
144
grid_map::GridMapRosConverter::fromOccupancyGrid (occupancy_grid, " layer" , grid_map);
146
145
147
146
if (params.occlusion_ignore_behind_predicted_objects )
148
- clear_behind_objects (grid_map, dynamic_objects, params.occlusion_min_objects_velocity , params.occlusion_extra_objects_size );
147
+ clear_behind_objects (
148
+ grid_map, dynamic_objects, params.occlusion_min_objects_velocity ,
149
+ params.occlusion_extra_objects_size );
149
150
const auto min_nb_of_cells = std::ceil (params.occlusion_min_size / grid_map.getResolution ());
150
151
for (const auto & detection_area : calculate_detection_areas (
151
152
crosswalk_lanelet, {path_intersection.x , path_intersection.y }, detection_range)) {
0 commit comments