Skip to content

Commit c5c0642

Browse files
refactor(autoware_compare_map_segmentation): resolve clang-tidy error in autoware_compare_map_segmentation (autowarefoundation#9162)
* refactor(autoware_compare_map_segmentation): resolve clang-tidy error in autoware_compare_map_segmentation Signed-off-by: Y.Hisaki <[email protected]> * style(pre-commit): autofix * include message_filters as SYSTEM Signed-off-by: Y.Hisaki <[email protected]> * style(pre-commit): autofix --------- Signed-off-by: Y.Hisaki <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent e2dc86e commit c5c0642

File tree

13 files changed

+36
-47
lines changed

13 files changed

+36
-47
lines changed

perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,9 +29,7 @@
2929
#include <pcl_conversions/pcl_conversions.h>
3030
#include <rcutils/filesystem.h> // To be replaced by std::filesystem in C++17
3131

32-
#include <memory>
3332
#include <string>
34-
#include <utility>
3533

3634
namespace autoware::compare_map_segmentation
3735
{

perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.hpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,7 @@
2424

2525
#include <grid_map_msgs/msg/grid_map.hpp>
2626

27-
#include <iostream>
28-
#include <memory>
29-
#include <mutex>
3027
#include <string>
31-
#include <vector>
3228
namespace autoware::compare_map_segmentation
3329
{
3430
class CompareElevationMapFilterComponent : public autoware::pointcloud_preprocessor::Filter

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -51,10 +51,10 @@ bool DistanceBasedStaticMapLoader::is_close_to_map(
5151
if (!is_initialized_.load(std::memory_order_acquire)) {
5252
return false;
5353
}
54-
if (map_ptr_ == NULL) {
54+
if (map_ptr_ == nullptr) {
5555
return false;
5656
}
57-
if (tree_ == NULL) {
57+
if (tree_ == nullptr) {
5858
return false;
5959
}
6060

@@ -89,8 +89,8 @@ bool DistanceBasedDynamicMapLoader::is_close_to_map(
8989
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
9090
return false;
9191
}
92-
if (current_voxel_grid_array_.at(map_grid_index) != NULL) {
93-
if (current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree == NULL) {
92+
if (current_voxel_grid_array_.at(map_grid_index) != nullptr) {
93+
if (current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree == nullptr) {
9494
return false;
9595
}
9696
std::vector<int> nn_indices(1);

perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,14 +24,13 @@
2424

2525
#include <memory>
2626
#include <string>
27-
#include <vector>
2827

2928
namespace autoware::compare_map_segmentation
3029
{
3130

32-
typedef typename pcl::Filter<pcl::PointXYZ>::PointCloud PointCloud;
33-
typedef typename PointCloud::Ptr PointCloudPtr;
34-
typedef typename PointCloud::ConstPtr PointCloudConstPtr;
31+
using PointCloud = typename pcl::Filter<pcl::PointXYZ>::PointCloud;
32+
using PointCloudPtr = typename PointCloud::Ptr;
33+
using PointCloudConstPtr = typename PointCloud::ConstPtr;
3534

3635
class DistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader
3736
{
@@ -102,8 +101,8 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
102101
class DistanceBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter
103102
{
104103
protected:
105-
virtual void filter(
106-
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output);
104+
void filter(
105+
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override;
107106

108107
private:
109108
double distance_threshold_;

perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ namespace autoware::compare_map_segmentation
2929
bool VoxelBasedApproximateStaticMapLoader::is_close_to_map(
3030
const pcl::PointXYZ & point, [[maybe_unused]] const double distance_threshold)
3131
{
32-
if (voxel_map_ptr_ == NULL) {
32+
if (voxel_map_ptr_ == nullptr) {
3333
return false;
3434
}
3535
const int index =
@@ -55,7 +55,7 @@ bool VoxelBasedApproximateDynamicMapLoader::is_close_to_map(
5555
if (static_cast<size_t>(map_grid_index) >= current_voxel_grid_array_.size()) {
5656
return false;
5757
}
58-
if (current_voxel_grid_array_.at(map_grid_index) != NULL) {
58+
if (current_voxel_grid_array_.at(map_grid_index) != nullptr) {
5959
const int index = current_voxel_grid_array_.at(map_grid_index)
6060
->map_cell_voxel_grid.getCentroidIndexAt(
6161
current_voxel_grid_array_.at(map_grid_index)

perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@
2323

2424
#include <memory>
2525
#include <string>
26-
#include <vector>
2726

2827
namespace autoware::compare_map_segmentation
2928
{
@@ -59,8 +58,8 @@ class VoxelBasedApproximateCompareMapFilterComponent
5958
: public autoware::pointcloud_preprocessor::Filter
6059
{
6160
protected:
62-
virtual void filter(
63-
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output);
61+
void filter(
62+
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override;
6463

6564
private:
6665
double distance_threshold_;

perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,9 @@
2222
#include <pcl/segmentation/segment_differences.h>
2323

2424
#include <string>
25-
#include <vector>
2625

2726
namespace autoware::compare_map_segmentation
2827
{
29-
using autoware::pointcloud_preprocessor::get_param;
3028

3129
VoxelBasedCompareMapFilterComponent::VoxelBasedCompareMapFilterComponent(
3230
const rclcpp::NodeOptions & options)

perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,15 +22,14 @@
2222
#include <pcl/search/pcl_search.h>
2323

2424
#include <memory>
25-
#include <vector>
2625

2726
namespace autoware::compare_map_segmentation
2827
{
2928
class VoxelBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter
3029
{
3130
protected:
32-
virtual void filter(
33-
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output);
31+
void filter(
32+
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override;
3433

3534
private:
3635
// pcl::SegmentDifferences<pcl::PointXYZ> impl_;
@@ -39,8 +38,6 @@ class VoxelBasedCompareMapFilterComponent : public autoware::pointcloud_preproce
3938
double distance_threshold_;
4039
bool set_map_in_voxel_grid_;
4140

42-
bool dynamic_map_load_enable_;
43-
4441
public:
4542
PCL_MAKE_ALIGNED_OPERATOR_NEW
4643
explicit VoxelBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options);

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -61,13 +61,13 @@ bool VoxelDistanceBasedStaticMapLoader::is_close_to_map(
6161
if (!is_initialized_.load(std::memory_order_acquire)) {
6262
return false;
6363
}
64-
if (voxel_map_ptr_ == NULL) {
64+
if (voxel_map_ptr_ == nullptr) {
6565
return false;
6666
}
67-
if (map_ptr_ == NULL) {
67+
if (map_ptr_ == nullptr) {
6868
return false;
6969
}
70-
if (tree_ == NULL) {
70+
if (tree_ == nullptr) {
7171
return false;
7272
}
7373
if (is_close_to_neighbor_voxels(point, distance_threshold, voxel_grid_, tree_)) {
@@ -91,7 +91,7 @@ bool VoxelDistanceBasedDynamicMapLoader::is_close_to_map(
9191
return false;
9292
}
9393
if (
94-
current_voxel_grid_array_.at(map_grid_index) != NULL &&
94+
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
9595
is_close_to_neighbor_voxels(
9696
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid,
9797
current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree)) {

perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,13 @@
2525
#include <memory>
2626
#include <string>
2727
#include <utility>
28-
#include <vector>
2928

3029
namespace autoware::compare_map_segmentation
3130
{
3231

33-
typedef typename pcl::Filter<pcl::PointXYZ>::PointCloud PointCloud;
34-
typedef typename PointCloud::Ptr PointCloudPtr;
35-
typedef typename PointCloud::ConstPtr PointCloudConstPtr;
32+
using PointCloud = typename pcl::Filter<pcl::PointXYZ>::PointCloud;
33+
using PointCloudPtr = typename PointCloud::Ptr;
34+
using PointCloudConstPtr = typename PointCloud::ConstPtr;
3635

3736
class VoxelDistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader
3837
{
@@ -124,8 +123,8 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader
124123
class VoxelDistanceBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter
125124
{
126125
protected:
127-
virtual void filter(
128-
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output);
126+
void filter(
127+
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override;
129128

130129
void input_target_callback(const PointCloud2ConstPtr map);
131130

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
4747
if (index != -1) {
4848
return true;
4949
}
50-
if (tree == NULL) {
50+
if (tree == nullptr) {
5151
return false;
5252
}
5353
std::vector<int> nn_indices(1);
@@ -64,7 +64,7 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
6464
{
6565
// check map downsampled pc
6666
double distance_threshold_z = downsize_ratio_z_axis_ * distance_threshold;
67-
if (map == NULL) {
67+
if (map == nullptr) {
6868
return false;
6969
}
7070
if (is_in_voxel(
@@ -331,7 +331,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid(
331331
if (
332332
static_cast<size_t>(neighbor_map_grid_index) >= current_voxel_grid_array_.size() ||
333333
neighbor_map_grid_index == current_map_grid_index ||
334-
current_voxel_grid_array_.at(neighbor_map_grid_index) != NULL) {
334+
current_voxel_grid_array_.at(neighbor_map_grid_index) != nullptr) {
335335
return false;
336336
}
337337
if (is_close_to_neighbor_voxels(
@@ -360,7 +360,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_map(
360360
return false;
361361
}
362362
if (
363-
current_voxel_grid_array_.at(map_grid_index) != NULL &&
363+
current_voxel_grid_array_.at(map_grid_index) != nullptr &&
364364
is_close_to_neighbor_voxels(
365365
point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr,
366366
current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) {

perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,6 @@
3030
#include <map>
3131
#include <memory>
3232
#include <string>
33-
#include <thread>
3433
#include <utility>
3534
#include <vector>
3635

@@ -93,13 +92,15 @@ class VoxelGridMapLoader
9392
bool debug_ = false;
9493

9594
public:
96-
typedef VoxelGridEx<pcl::PointXYZ> VoxelGridPointXYZ;
97-
typedef typename pcl::Filter<pcl::PointXYZ>::PointCloud PointCloud;
98-
typedef typename PointCloud::Ptr PointCloudPtr;
95+
using VoxelGridPointXYZ = VoxelGridEx<pcl::PointXYZ>;
96+
using PointCloud = typename pcl::Filter<pcl::PointXYZ>::PointCloud;
97+
using PointCloudPtr = typename PointCloud::Ptr;
9998
explicit VoxelGridMapLoader(
10099
rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis,
101100
std::string * tf_map_input_frame);
102101

102+
virtual ~VoxelGridMapLoader() = default;
103+
103104
virtual bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) = 0;
104105
static bool is_close_to_neighbor_voxels(
105106
const pcl::PointXYZ & point, const double distance_threshold, VoxelGridPointXYZ & voxel,
@@ -142,7 +143,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
142143
pcl::search::Search<pcl::PointXYZ>::Ptr map_cell_kdtree;
143144
};
144145

145-
typedef typename std::map<std::string, struct MapGridVoxelInfo> VoxelGridDict;
146+
using VoxelGridDict = typename std::map<std::string, struct MapGridVoxelInfo>;
146147

147148
/** \brief Map to hold loaded map grid id and it's voxel filter */
148149
VoxelGridDict current_voxel_grid_dict_;

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@ target_include_directories(pointcloud_preprocessor_filter_base PUBLIC
3636
)
3737

3838
ament_target_dependencies(pointcloud_preprocessor_filter_base
39+
SYSTEM
3940
message_filters
4041
pcl_conversions
4142
rclcpp
@@ -56,6 +57,7 @@ target_include_directories(faster_voxel_grid_downsample_filter PUBLIC
5657
)
5758

5859
ament_target_dependencies(faster_voxel_grid_downsample_filter
60+
SYSTEM
5961
pcl_conversions
6062
rclcpp
6163
sensor_msgs

0 commit comments

Comments
 (0)