From 46b11ac7b342029e4d15179ecb917914eab11884 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 5 Mar 2025 14:59:59 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../CMakeLists.txt | 2 +- ...ed_faster_voxel_grid_downsample_filter.hpp | 29 ++++++++++++------- ...uded_voxel_grid_downsample_filter_node.hpp | 14 ++++----- ...ed_faster_voxel_grid_downsample_filter.cpp | 8 ++--- ...uded_voxel_grid_downsample_filter_node.cpp | 15 ++++++---- .../src/filter.cpp | 3 +- 6 files changed, 43 insertions(+), 28 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index cd048bd6c4959..ddd0d589b03ce 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -90,7 +90,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/downsample_filter/random_downsample_filter_node.cpp src/downsample_filter/approximate_downsample_filter_node.cpp src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp - src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp + src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp src/outlier_filter/ring_outlier_filter_node.cpp src/outlier_filter/radius_search_2d_outlier_filter_node.cpp src/outlier_filter/voxel_grid_outlier_filter_node.cpp diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp index a6a9c8bd2b1bc..5573477e13640 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp @@ -15,15 +15,18 @@ #pragma once #include "autoware/pointcloud_preprocessor/transform_info.hpp" + +#include + #include #include #include -#include -#include -#include + #include #include -#include +#include +#include +#include namespace autoware::pointcloud_preprocessor { @@ -39,8 +42,8 @@ class RoiExcludedFasterVoxelGridDownsampleFilter // renamed class void set_field_offsets(const PointCloud2ConstPtr & input, const rclcpp::Logger & logger); void set_roi(float x_min, float x_max, float y_min, float y_max); void filter( - const PointCloud2ConstPtr & input, PointCloud2 & output, - const TransformInfo & transform_info, const rclcpp::Logger & logger); + const PointCloud2ConstPtr & input, PointCloud2 & output, const TransformInfo & transform_info, + const rclcpp::Logger & logger); private: struct Centroid @@ -52,15 +55,21 @@ class RoiExcludedFasterVoxelGridDownsampleFilter // renamed class uint32_t point_count_; Centroid() : x(0), y(0), z(0), intensity(0), point_count_(0) {} Centroid(float _x, float _y, float _z, float _intensity) - : x(_x), y(_y), z(_z), intensity(_intensity), point_count_(1) {} + : x(_x), y(_y), z(_z), intensity(_intensity), point_count_(1) + { + } void add_point(float _x, float _y, float _z, float _intensity) { - x += _x; y += _y; z += _z; intensity += _intensity; + x += _x; + y += _y; + z += _z; + intensity += _intensity; point_count_++; } Eigen::Vector4f calc_centroid() const { - return Eigen::Vector4f(x/point_count_, y/point_count_, z/point_count_, intensity/point_count_); + return Eigen::Vector4f( + x / point_count_, y / point_count_, z / point_count_, intensity / point_count_); } }; @@ -88,4 +97,4 @@ class RoiExcludedFasterVoxelGridDownsampleFilter // renamed class const TransformInfo & transform_info); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp index ae493d87daca2..8ec89c04ec408 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODE_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODE_HPP_ #include "autoware/pointcloud_preprocessor/filter.hpp" #include "autoware/pointcloud_preprocessor/transform_info.hpp" -#include #include +#include #include #include @@ -35,8 +35,8 @@ class RoiExcludedVoxelGridDownsampleFilterComponent : public Filter void filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; void faster_filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, - PointCloud2 & output, const TransformInfo & transform_info) override; + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, + const TransformInfo & transform_info) override; private: float voxel_size_x_; @@ -52,6 +52,6 @@ class RoiExcludedVoxelGridDownsampleFilterComponent : public Filter const std::vector & parameters); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ \ No newline at end of file +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODE_HPP_ diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.cpp index cf294d3607ff9..d9075af8d80f3 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.cpp @@ -14,10 +14,10 @@ #include "autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp" -#include +#include #include -#include +#include namespace autoware::pointcloud_preprocessor { @@ -89,7 +89,7 @@ bool RoiExcludedFasterVoxelGridDownsampleFilter::get_min_max_voxel( max_point = max_point.cwiseMax(point.head<3>()); } } - + if ( ((static_cast((max_point[0] - min_point[0]) * inverse_voxel_size_[0]) + 1) * (static_cast((max_point[1] - min_point[1]) * inverse_voxel_size_[1]) + 1) * @@ -235,4 +235,4 @@ void RoiExcludedFasterVoxelGridDownsampleFilter::filter( output.data.begin() + downsampled_filtered.data.size()); } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp index aa2dcc6b251cd..aa07143e20102 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp @@ -13,8 +13,11 @@ // limitations under the License. #include "autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp" + #include "autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp" + #include + #include #include @@ -49,8 +52,8 @@ void RoiExcludedVoxelGridDownsampleFilterComponent::filter( } void RoiExcludedVoxelGridDownsampleFilterComponent::faster_filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, - PointCloud2 & output, const TransformInfo & transform_info) + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, + const TransformInfo & transform_info) { std::scoped_lock lock(mutex_); if (indices) { @@ -63,7 +66,8 @@ void RoiExcludedVoxelGridDownsampleFilterComponent::faster_filter( roi_excluded_filter.filter(input, output, transform_info, this->get_logger()); } -rcl_interfaces::msg::SetParametersResult RoiExcludedVoxelGridDownsampleFilterComponent::paramCallback( +rcl_interfaces::msg::SetParametersResult +RoiExcludedVoxelGridDownsampleFilterComponent::paramCallback( const std::vector & parameters) { std::scoped_lock lock(mutex_); @@ -94,7 +98,8 @@ rcl_interfaces::msg::SetParametersResult RoiExcludedVoxelGridDownsampleFilterCom return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::RoiExcludedVoxelGridDownsampleFilterComponent) \ No newline at end of file +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::RoiExcludedVoxelGridDownsampleFilterComponent) diff --git a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp index 4f77c2624862c..c4ff45d652044 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp @@ -140,7 +140,8 @@ void autoware::pointcloud_preprocessor::Filter::subscribe(const std::string & fi // each time a child class supports the faster version. // When all the child classes support the faster version, this workaround is deleted. std::set supported_nodes = { - "CropBoxFilter", "RingOutlierFilter", "VoxelGridDownsampleFilter", "ScanGroundFilter", "RoiExcludedVoxelGridDownsampleFilter"}; + "CropBoxFilter", "RingOutlierFilter", "VoxelGridDownsampleFilter", "ScanGroundFilter", + "RoiExcludedVoxelGridDownsampleFilter"}; auto callback = supported_nodes.find(filter_name) != supported_nodes.end() ? &Filter::faster_input_indices_callback : &Filter::input_indices_callback;