From 789bf724dc70686bc3698512b0a98823739f45f6 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Wed, 24 Jan 2024 14:38:19 +0900 Subject: [PATCH] pre-commit Signed-off-by: Maxime CLEMENT --- .../behavior_velocity_crosswalk_module/src/manager.cpp | 2 +- .../src/occluded_crosswalk.cpp | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 283e5127e4dd0..f5d8f3148e1e0 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -142,7 +142,7 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".occlusion.ignore_behind_predicted_objects"); cp.occlusion_min_objects_velocity = getOrDeclareParameter(node, ns + ".occlusion.min_objects_velocity"); - cp.occlusion_extra_objects_size= + cp.occlusion_extra_objects_size = getOrDeclareParameter(node, ns + ".occlusion.extra_objects_size"); } diff --git a/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp index f2fefac5f6de6..867245437a2fb 100644 --- a/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp @@ -117,8 +117,7 @@ void clear_behind_objects( lanelet::geometry::distance2d(grid_map_position, object_position) < range) { lanelet::BasicPoints2d edge_points; const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); - for (const auto & edge_point : object_polygon.outer()) - edge_points.push_back(edge_point); + for (const auto & edge_point : object_polygon.outer()) edge_points.push_back(edge_point); std::sort(edge_points.begin(), edge_points.end(), angle_cmp); // points.push_back(interpolate_point({object_position, edge_point}, 10.0 * range)); grid_map::Polygon polygon_to_clear; @@ -145,7 +144,9 @@ bool is_crosswalk_occluded( grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map); if (params.occlusion_ignore_behind_predicted_objects) - clear_behind_objects(grid_map, dynamic_objects, params.occlusion_min_objects_velocity, params.occlusion_extra_objects_size); + clear_behind_objects( + grid_map, dynamic_objects, params.occlusion_min_objects_velocity, + params.occlusion_extra_objects_size); const auto min_nb_of_cells = std::ceil(params.occlusion_min_size / grid_map.getResolution()); for (const auto & detection_area : calculate_detection_areas( crosswalk_lanelet, {path_intersection.x, path_intersection.y}, detection_range)) {