Skip to content

Commit 4d0709b

Browse files
committed
pre-commit
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 15f39ab commit 4d0709b

File tree

2 files changed

+5
-4
lines changed

2 files changed

+5
-4
lines changed

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,7 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
142142
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
143143
cp.occlusion_min_objects_velocity =
144144
getOrDeclareParameter<double>(node, ns + ".occlusion.min_objects_velocity");
145-
cp.occlusion_extra_objects_size=
145+
cp.occlusion_extra_objects_size =
146146
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_objects_size");
147147
}
148148

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -117,8 +117,7 @@ void clear_behind_objects(
117117
lanelet::geometry::distance2d(grid_map_position, object_position) < range) {
118118
lanelet::BasicPoints2d edge_points;
119119
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);
122121
std::sort(edge_points.begin(), edge_points.end(), angle_cmp);
123122
// points.push_back(interpolate_point({object_position, edge_point}, 10.0 * range));
124123
grid_map::Polygon polygon_to_clear;
@@ -145,7 +144,9 @@ bool is_crosswalk_occluded(
145144
grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map);
146145

147146
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);
149150
const auto min_nb_of_cells = std::ceil(params.occlusion_min_size / grid_map.getResolution());
150151
for (const auto & detection_area : calculate_detection_areas(
151152
crosswalk_lanelet, {path_intersection.x, path_intersection.y}, detection_range)) {

0 commit comments

Comments
 (0)