Skip to content

Commit 46b11ac

Browse files
style(pre-commit): autofix
1 parent dc96513 commit 46b11ac

File tree

6 files changed

+43
-28
lines changed

6 files changed

+43
-28
lines changed

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
9090
src/downsample_filter/random_downsample_filter_node.cpp
9191
src/downsample_filter/approximate_downsample_filter_node.cpp
9292
src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp
93-
src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp
93+
src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp
9494
src/outlier_filter/ring_outlier_filter_node.cpp
9595
src/outlier_filter/radius_search_2d_outlier_filter_node.cpp
9696
src/outlier_filter/voxel_grid_outlier_filter_node.cpp

sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp

+19-10
Original file line numberDiff line numberDiff line change
@@ -15,15 +15,18 @@
1515
#pragma once
1616

1717
#include "autoware/pointcloud_preprocessor/transform_info.hpp"
18+
19+
#include <Eigen/Core>
20+
1821
#include <pcl/filters/voxel_grid.h>
1922
#include <pcl_conversions/pcl_conversions.h>
2023
#include <sensor_msgs/msg/point_cloud2.h>
21-
#include <unordered_map>
22-
#include <vector>
23-
#include <limits>
24+
2425
#include <cfloat>
2526
#include <cmath>
26-
#include <Eigen/Core>
27+
#include <limits>
28+
#include <unordered_map>
29+
#include <vector>
2730

2831
namespace autoware::pointcloud_preprocessor
2932
{
@@ -39,8 +42,8 @@ class RoiExcludedFasterVoxelGridDownsampleFilter // renamed class
3942
void set_field_offsets(const PointCloud2ConstPtr & input, const rclcpp::Logger & logger);
4043
void set_roi(float x_min, float x_max, float y_min, float y_max);
4144
void filter(
42-
const PointCloud2ConstPtr & input, PointCloud2 & output,
43-
const TransformInfo & transform_info, const rclcpp::Logger & logger);
45+
const PointCloud2ConstPtr & input, PointCloud2 & output, const TransformInfo & transform_info,
46+
const rclcpp::Logger & logger);
4447

4548
private:
4649
struct Centroid
@@ -52,15 +55,21 @@ class RoiExcludedFasterVoxelGridDownsampleFilter // renamed class
5255
uint32_t point_count_;
5356
Centroid() : x(0), y(0), z(0), intensity(0), point_count_(0) {}
5457
Centroid(float _x, float _y, float _z, float _intensity)
55-
: x(_x), y(_y), z(_z), intensity(_intensity), point_count_(1) {}
58+
: x(_x), y(_y), z(_z), intensity(_intensity), point_count_(1)
59+
{
60+
}
5661
void add_point(float _x, float _y, float _z, float _intensity)
5762
{
58-
x += _x; y += _y; z += _z; intensity += _intensity;
63+
x += _x;
64+
y += _y;
65+
z += _z;
66+
intensity += _intensity;
5967
point_count_++;
6068
}
6169
Eigen::Vector4f calc_centroid() const
6270
{
63-
return Eigen::Vector4f(x/point_count_, y/point_count_, z/point_count_, intensity/point_count_);
71+
return Eigen::Vector4f(
72+
x / point_count_, y / point_count_, z / point_count_, intensity / point_count_);
6473
}
6574
};
6675

@@ -88,4 +97,4 @@ class RoiExcludedFasterVoxelGridDownsampleFilter // renamed class
8897
const TransformInfo & transform_info);
8998
};
9099

91-
} // namespace pointcloud_preprocessor
100+
} // namespace autoware::pointcloud_preprocessor

sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,14 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_
16-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_
15+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODE_HPP_
16+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODE_HPP_
1717

1818
#include "autoware/pointcloud_preprocessor/filter.hpp"
1919
#include "autoware/pointcloud_preprocessor/transform_info.hpp"
2020

21-
#include <rclcpp/rclcpp.hpp>
2221
#include <rcl_interfaces/msg/set_parameters_result.hpp>
22+
#include <rclcpp/rclcpp.hpp>
2323

2424
#include <mutex>
2525
#include <vector>
@@ -35,8 +35,8 @@ class RoiExcludedVoxelGridDownsampleFilterComponent : public Filter
3535
void filter(
3636
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override;
3737
void faster_filter(
38-
const PointCloud2ConstPtr & input, const IndicesPtr & indices,
39-
PointCloud2 & output, const TransformInfo & transform_info) override;
38+
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output,
39+
const TransformInfo & transform_info) override;
4040

4141
private:
4242
float voxel_size_x_;
@@ -52,6 +52,6 @@ class RoiExcludedVoxelGridDownsampleFilterComponent : public Filter
5252
const std::vector<rclcpp::Parameter> & parameters);
5353
};
5454

55-
} // namespace pointcloud_preprocessor
55+
} // namespace autoware::pointcloud_preprocessor
5656

57-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_
57+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__ROI_EXCLUDED_VOXEL_GRID_DOWNSAMPLE_FILTER_NODE_HPP_

sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -14,10 +14,10 @@
1414

1515
#include "autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp"
1616

17-
#include <Eigen/Dense>
17+
#include <Eigen/Dense>
1818
#include <rclcpp/rclcpp.hpp>
1919

20-
#include <cfloat>
20+
#include <cfloat>
2121

2222
namespace autoware::pointcloud_preprocessor
2323
{
@@ -89,7 +89,7 @@ bool RoiExcludedFasterVoxelGridDownsampleFilter::get_min_max_voxel(
8989
max_point = max_point.cwiseMax(point.head<3>());
9090
}
9191
}
92-
92+
9393
if (
9494
((static_cast<std::int64_t>((max_point[0] - min_point[0]) * inverse_voxel_size_[0]) + 1) *
9595
(static_cast<std::int64_t>((max_point[1] - min_point[1]) * inverse_voxel_size_[1]) + 1) *
@@ -235,4 +235,4 @@ void RoiExcludedFasterVoxelGridDownsampleFilter::filter(
235235
output.data.begin() + downsampled_filtered.data.size());
236236
}
237237

238-
} // namespace pointcloud_preprocessor
238+
} // namespace autoware::pointcloud_preprocessor

sensing/autoware_pointcloud_preprocessor/src/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.cpp

+10-5
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,11 @@
1313
// limitations under the License.
1414

1515
#include "autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_voxel_grid_downsample_filter_node.hpp"
16+
1617
#include "autoware/pointcloud_preprocessor/downsample_filter/roi_excluded_faster_voxel_grid_downsample_filter.hpp"
18+
1719
#include <rclcpp/rclcpp.hpp>
20+
1821
#include <mutex>
1922
#include <vector>
2023

@@ -49,8 +52,8 @@ void RoiExcludedVoxelGridDownsampleFilterComponent::filter(
4952
}
5053

5154
void RoiExcludedVoxelGridDownsampleFilterComponent::faster_filter(
52-
const PointCloud2ConstPtr & input, const IndicesPtr & indices,
53-
PointCloud2 & output, const TransformInfo & transform_info)
55+
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output,
56+
const TransformInfo & transform_info)
5457
{
5558
std::scoped_lock lock(mutex_);
5659
if (indices) {
@@ -63,7 +66,8 @@ void RoiExcludedVoxelGridDownsampleFilterComponent::faster_filter(
6366
roi_excluded_filter.filter(input, output, transform_info, this->get_logger());
6467
}
6568

66-
rcl_interfaces::msg::SetParametersResult RoiExcludedVoxelGridDownsampleFilterComponent::paramCallback(
69+
rcl_interfaces::msg::SetParametersResult
70+
RoiExcludedVoxelGridDownsampleFilterComponent::paramCallback(
6771
const std::vector<rclcpp::Parameter> & parameters)
6872
{
6973
std::scoped_lock lock(mutex_);
@@ -94,7 +98,8 @@ rcl_interfaces::msg::SetParametersResult RoiExcludedVoxelGridDownsampleFilterCom
9498
return result;
9599
}
96100

97-
} // namespace pointcloud_preprocessor
101+
} // namespace autoware::pointcloud_preprocessor
98102

99103
#include <rclcpp_components/register_node_macro.hpp>
100-
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::RoiExcludedVoxelGridDownsampleFilterComponent)
104+
RCLCPP_COMPONENTS_REGISTER_NODE(
105+
autoware::pointcloud_preprocessor::RoiExcludedVoxelGridDownsampleFilterComponent)

sensing/autoware_pointcloud_preprocessor/src/filter.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,8 @@ void autoware::pointcloud_preprocessor::Filter::subscribe(const std::string & fi
140140
// each time a child class supports the faster version.
141141
// When all the child classes support the faster version, this workaround is deleted.
142142
std::set<std::string> supported_nodes = {
143-
"CropBoxFilter", "RingOutlierFilter", "VoxelGridDownsampleFilter", "ScanGroundFilter", "RoiExcludedVoxelGridDownsampleFilter"};
143+
"CropBoxFilter", "RingOutlierFilter", "VoxelGridDownsampleFilter", "ScanGroundFilter",
144+
"RoiExcludedVoxelGridDownsampleFilter"};
144145
auto callback = supported_nodes.find(filter_name) != supported_nodes.end()
145146
? &Filter::faster_input_indices_callback
146147
: &Filter::input_indices_callback;

0 commit comments

Comments
 (0)