Skip to content

Commit

Permalink
pre-commit
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem committed Jan 24, 2024
1 parent 12710a9 commit 789bf72
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
cp.occlusion_min_objects_velocity =
getOrDeclareParameter<double>(node, ns + ".occlusion.min_objects_velocity");
cp.occlusion_extra_objects_size=
cp.occlusion_extra_objects_size =
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_objects_size");
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Check warning on line 121 in planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp#L121

Added line #L121 was not covered by tests
// points.push_back(interpolate_point({object_position, edge_point}, 10.0 * range));
grid_map::Polygon polygon_to_clear;
Expand All @@ -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,

Check warning on line 148 in planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp#L147-L148

Added lines #L147 - L148 were not covered by tests
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(

Check warning on line 151 in planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp#L151

Added line #L151 was not covered by tests
crosswalk_lanelet, {path_intersection.x, path_intersection.y}, detection_range)) {
Expand Down

0 comments on commit 789bf72

Please sign in to comment.