From 5ad8ae0b9c337c1830b5cf8084f578a8d7f6a19e Mon Sep 17 00:00:00 2001
From: Anh Nguyen <anh.nguyen.2@tier4.jp>
Date: Fri, 9 Aug 2024 12:59:17 +0700
Subject: [PATCH] Applied clang format 17.0.5

Signed-off-by: Anh Nguyen <anh.nguyen.2@tier4.jp>
---
 include/multigrid_pclomp/multigrid_ndt_omp.h  |  98 +++------------
 include/pclomp/gicp_omp.h                     |  30 +----
 include/pclomp/ndt_omp.h                      | 119 ++++--------------
 include/pclomp/voxel_grid_covariance_omp.h    |  20 +--
 .../pclomp/voxel_grid_covariance_omp_impl.hpp |   4 +-
 5 files changed, 56 insertions(+), 215 deletions(-)

diff --git a/include/multigrid_pclomp/multigrid_ndt_omp.h b/include/multigrid_pclomp/multigrid_ndt_omp.h
index 9f0b6e1..48a89f8 100644
--- a/include/multigrid_pclomp/multigrid_ndt_omp.h
+++ b/include/multigrid_pclomp/multigrid_ndt_omp.h
@@ -125,9 +125,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
     MultiGridNormalDistributionsTransform && other) noexcept;
 
   /** \brief Empty destructor */
-  virtual ~MultiGridNormalDistributionsTransform()
-  {
-  }
+  virtual ~MultiGridNormalDistributionsTransform() {}
 
   void setNumThreads(int n)
   {
@@ -136,10 +134,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
     target_cells_.setThreadNum(params_.num_threads);
   }
 
-  inline int getNumThreads() const
-  {
-    return params_.num_threads;
-  }
+  inline int getNumThreads() const { return params_.num_threads; }
 
   inline void setInputSource(const PointCloudSourceConstPtr & input)
   {
@@ -170,10 +165,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
     target_cells_.setInputCloudAndFilter(cloud, target_id);
   }
 
-  inline void removeTarget(const std::string target_id)
-  {
-    target_cells_.removeCloud(target_id);
-  }
+  inline void removeTarget(const std::string target_id) { target_cells_.removeCloud(target_id); }
 
   inline void createVoxelKdtree()
   {
@@ -196,50 +188,32 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
   /** \brief Get voxel grid resolution.
    * \return side length of voxels
    */
-  inline float getResolution() const
-  {
-    return (params_.resolution);
-  }
+  inline float getResolution() const { return (params_.resolution); }
 
   /** \brief Get the newton line search maximum step length.
    * \return maximum step length
    */
-  inline double getStepSize() const
-  {
-    return (params_.step_size);
-  }
+  inline double getStepSize() const { return (params_.step_size); }
 
   /** \brief Set/change the newton line search maximum step length.
    * \param[in] step_size maximum step length
    */
-  inline void setStepSize(double step_size)
-  {
-    params_.step_size = step_size;
-  }
+  inline void setStepSize(double step_size) { params_.step_size = step_size; }
 
   /** \brief Get the point cloud outlier ratio.
    * \return outlier ratio
    */
-  inline double getOutlierRatio() const
-  {
-    return (outlier_ratio_);
-  }
+  inline double getOutlierRatio() const { return (outlier_ratio_); }
 
   /** \brief Set/change the point cloud outlier ratio.
    * \param[in] outlier_ratio outlier ratio
    */
-  inline void setOutlierRatio(double outlier_ratio)
-  {
-    outlier_ratio_ = outlier_ratio;
-  }
+  inline void setOutlierRatio(double outlier_ratio) { outlier_ratio_ = outlier_ratio; }
 
   /** \brief Get the registration alignment probability.
    * \return transformation probability
    */
-  inline double getTransformationProbability() const
-  {
-    return (trans_probability_);
-  }
+  inline double getTransformationProbability() const { return (trans_probability_); }
 
   inline double getNearestVoxelTransformationLikelihood() const
   {
@@ -249,16 +223,10 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
   /** \brief Get the number of iterations required to calculate alignment.
    * \return final number of iterations
    */
-  inline int getFinalNumIteration() const
-  {
-    return (nr_iterations_);
-  }
+  inline int getFinalNumIteration() const { return (nr_iterations_); }
 
   /** \brief Return the hessian matrix */
-  inline Eigen::Matrix<double, 6, 6> getHessian() const
-  {
-    return hessian_;
-  }
+  inline Eigen::Matrix<double, 6, 6> getHessian() const { return hessian_; }
 
   /** \brief Return the transformation array */
   inline const std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>> &
@@ -305,10 +273,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
     regularization_pose_ = regularization_pose;
   }
 
-  inline void unsetRegularizationPose()
-  {
-    regularization_pose_ = boost::none;
-  }
+  inline void unsetRegularizationPose() { regularization_pose_ = boost::none; }
 
   NdtResult getResult()
   {
@@ -331,18 +296,12 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
    * transformation epsilon in order for an optimization to be considered as having
    * converged to the final solution.
    */
-  inline void setTransformationEpsilon(double epsilon)
-  {
-    params_.trans_epsilon = epsilon;
-  }
+  inline void setTransformationEpsilon(double epsilon) { params_.trans_epsilon = epsilon; }
 
   /** \brief Get the transformation epsilon (maximum allowable translation squared
    * difference between two consecutive transformations) as set by the user.
    */
-  inline double getTransformationEpsilon()
-  {
-    return (params_.trans_epsilon);
-  }
+  inline double getTransformationEpsilon() { return (params_.trans_epsilon); }
 
   inline void setMaximumIterations(int max_iterations)
   {
@@ -350,15 +309,9 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
     max_iterations_ = params_.max_iterations;
   }
 
-  inline int getMaxIterations() const
-  {
-    return params_.max_iterations;
-  }
+  inline int getMaxIterations() const { return params_.max_iterations; }
 
-  inline int getMaxIterations()
-  {
-    return params_.max_iterations;
-  }
+  inline int getMaxIterations() { return params_.max_iterations; }
 
   void setParams(const NdtParams & ndt_params)
   {
@@ -368,20 +321,11 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
     target_cells_.setThreadNum(params_.num_threads);
   }
 
-  NdtParams getParams() const
-  {
-    return params_;
-  }
+  NdtParams getParams() const { return params_; }
 
-  pcl::PointCloud<PointTarget> getVoxelPCD() const
-  {
-    return target_cells_.getVoxelPCD();
-  }
+  pcl::PointCloud<PointTarget> getVoxelPCD() const { return target_cells_.getVoxelPCD(); }
 
-  std::vector<std::string> getCurrentMapIDs() const
-  {
-    return target_cells_.getCurrentMapIDs();
-  }
+  std::vector<std::string> getCurrentMapIDs() const { return target_cells_.getCurrentMapIDs(); }
 
 protected:
   using BaseRegType::converged_;
@@ -413,9 +357,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
   virtual void computeTransformation(PointCloudSource & output, const Eigen::Matrix4f & guess);
 
   /** \brief Initiate covariance voxel structure. */
-  void inline init()
-  {
-  }
+  void inline init() {}
 
   /** \brief Compute derivatives of probability function w.r.t. the transformation vector.
    * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
diff --git a/include/pclomp/gicp_omp.h b/include/pclomp/gicp_omp.h
index 1e05274..c71d77e 100644
--- a/include/pclomp/gicp_omp.h
+++ b/include/pclomp/gicp_omp.h
@@ -217,18 +217,12 @@ class GeneralizedIterativeClosestPoint : public pcl::IterativeClosestPoint<Point
    * converged to the final solution.
    * \param epsilon the rotation epsilon
    */
-  inline void setRotationEpsilon(double epsilon)
-  {
-    rotation_epsilon_ = epsilon;
-  }
+  inline void setRotationEpsilon(double epsilon) { rotation_epsilon_ = epsilon; }
 
   /** \brief Get the rotation epsilon (maximum allowable difference between two
    * consecutive rotations) as set by the user.
    */
-  inline double getRotationEpsilon()
-  {
-    return (rotation_epsilon_);
-  }
+  inline double getRotationEpsilon() { return (rotation_epsilon_); }
 
   /** \brief Set the number of neighbors used when selecting a point neighbourhood
    * to compute covariances.
@@ -236,32 +230,20 @@ class GeneralizedIterativeClosestPoint : public pcl::IterativeClosestPoint<Point
    * covariances computation slower.
    * \param k the number of neighbors to use when computing covariances
    */
-  void setCorrespondenceRandomness(int k)
-  {
-    k_correspondences_ = k;
-  }
+  void setCorrespondenceRandomness(int k) { k_correspondences_ = k; }
 
   /** \brief Get the number of neighbors used when computing covariances as set by
    * the user
    */
-  int getCorrespondenceRandomness()
-  {
-    return (k_correspondences_);
-  }
+  int getCorrespondenceRandomness() { return (k_correspondences_); }
 
   /** set maximum number of iterations at the optimization step
    * \param[in] max maximum number of iterations for the optimizer
    */
-  void setMaximumOptimizerIterations(int max)
-  {
-    max_inner_iterations_ = max;
-  }
+  void setMaximumOptimizerIterations(int max) { max_inner_iterations_ = max; }
 
   ///\return maximum number of iterations at the optimization step
-  int getMaximumOptimizerIterations()
-  {
-    return (max_inner_iterations_);
-  }
+  int getMaximumOptimizerIterations() { return (max_inner_iterations_); }
 
 protected:
   /** \brief The number of neighbors used for covariances computation.
diff --git a/include/pclomp/ndt_omp.h b/include/pclomp/ndt_omp.h
index da0228f..8706215 100644
--- a/include/pclomp/ndt_omp.h
+++ b/include/pclomp/ndt_omp.h
@@ -114,19 +114,11 @@ class NormalDistributionsTransform : public pcl::Registration<PointSource, Point
   NormalDistributionsTransform();
 
   /** \brief Empty destructor */
-  virtual ~NormalDistributionsTransform()
-  {
-  }
+  virtual ~NormalDistributionsTransform() {}
 
-  void setNumThreads(int n)
-  {
-    params_.num_threads = n;
-  }
+  void setNumThreads(int n) { params_.num_threads = n; }
 
-  inline int getNumThreads() const
-  {
-    return params_.num_threads;
-  }
+  inline int getNumThreads() const { return params_.num_threads; }
 
   /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the
    * input source to). \param[in] cloud the input point cloud target
@@ -152,60 +144,39 @@ class NormalDistributionsTransform : public pcl::Registration<PointSource, Point
   /** \brief Get voxel grid resolution.
    * \return side length of voxels
    */
-  inline float getResolution() const
-  {
-    return (params_.resolution);
-  }
+  inline float getResolution() const { return (params_.resolution); }
 
   /** \brief Get the newton line search maximum step length.
    * \return maximum step length
    */
-  inline double getStepSize() const
-  {
-    return (params_.step_size);
-  }
+  inline double getStepSize() const { return (params_.step_size); }
 
   /** \brief Set/change the newton line search maximum step length.
    * \param[in] step_size maximum step length
    */
-  inline void setStepSize(double step_size)
-  {
-    params_.step_size = step_size;
-  }
+  inline void setStepSize(double step_size) { params_.step_size = step_size; }
 
   /** \brief Get the point cloud outlier ratio.
    * \return outlier ratio
    */
-  inline double getOutlierRatio() const
-  {
-    return (outlier_ratio_);
-  }
+  inline double getOutlierRatio() const { return (outlier_ratio_); }
 
   /** \brief Set/change the point cloud outlier ratio.
    * \param[in] outlier_ratio outlier ratio
    */
-  inline void setOutlierRatio(double outlier_ratio)
-  {
-    outlier_ratio_ = outlier_ratio;
-  }
+  inline void setOutlierRatio(double outlier_ratio) { outlier_ratio_ = outlier_ratio; }
 
   inline void setNeighborhoodSearchMethod(NeighborSearchMethod method)
   {
     params_.search_method = method;
   }
 
-  inline NeighborSearchMethod getNeighborhoodSearchMethod() const
-  {
-    return params_.search_method;
-  }
+  inline NeighborSearchMethod getNeighborhoodSearchMethod() const { return params_.search_method; }
 
   /** \brief Get the registration alignment probability.
    * \return transformation probability
    */
-  inline double getTransformationProbability() const
-  {
-    return (trans_probability_);
-  }
+  inline double getTransformationProbability() const { return (trans_probability_); }
 
   inline double getNearestVoxelTransformationLikelihood() const
   {
@@ -215,16 +186,10 @@ class NormalDistributionsTransform : public pcl::Registration<PointSource, Point
   /** \brief Get the number of iterations required to calculate alignment.
    * \return final number of iterations
    */
-  inline int getFinalNumIteration() const
-  {
-    return (nr_iterations_);
-  }
+  inline int getFinalNumIteration() const { return (nr_iterations_); }
 
   /** \brief Return the hessian matrix */
-  inline Eigen::Matrix<double, 6, 6> getHessian() const
-  {
-    return hessian_;
-  }
+  inline Eigen::Matrix<double, 6, 6> getHessian() const { return hessian_; }
 
   /** \brief Return the transformation array */
   inline const std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>> &
@@ -257,30 +222,15 @@ class NormalDistributionsTransform : public pcl::Registration<PointSource, Point
   }
 
   // add at 20220721 konishi
-  inline const std::vector<double> getScores() const
-  {
-    return scores_;
-  }
+  inline const std::vector<double> getScores() const { return scores_; }
 
-  inline const TargetGrid getTargetCells() const
-  {
-    return target_cells_;
-  }
+  inline const TargetGrid getTargetCells() const { return target_cells_; }
 
-  inline const std::map<size_t, double> getScoreMap() const
-  {
-    return voxel_score_map_;
-  }
+  inline const std::map<size_t, double> getScoreMap() const { return voxel_score_map_; }
 
-  inline const std::map<size_t, size_t> getNoPointMap() const
-  {
-    return nomap_points_num_;
-  }
+  inline const std::map<size_t, size_t> getNoPointMap() const { return nomap_points_num_; }
 
-  std::set<Eigen::Vector3i, EigenCmp> & getEmptyVoxels()
-  {
-    return empty_voxels_;
-  }
+  std::set<Eigen::Vector3i, EigenCmp> & getEmptyVoxels() { return empty_voxels_; }
 
   // For debug
   void cleanScores()
@@ -306,10 +256,7 @@ class NormalDistributionsTransform : public pcl::Registration<PointSource, Point
     regularization_pose_ = regularization_pose;
   }
 
-  inline void unsetRegularizationPose()
-  {
-    regularization_pose_ = boost::none;
-  }
+  inline void unsetRegularizationPose() { regularization_pose_ = boost::none; }
 
   NdtResult getResult()
   {
@@ -329,37 +276,19 @@ class NormalDistributionsTransform : public pcl::Registration<PointSource, Point
    * transformation epsilon in order for an optimization to be considered as having
    * converged to the final solution.
    */
-  inline void setTransformationEpsilon(double epsilon)
-  {
-    params_.trans_epsilon = epsilon;
-  }
+  inline void setTransformationEpsilon(double epsilon) { params_.trans_epsilon = epsilon; }
 
   /** \brief Get the transformation epsilon (maximum allowable translation squared
    * difference between two consecutive transformations) as set by the user.
    */
-  inline double getTransformationEpsilon()
-  {
-    return (params_.trans_epsilon);
-  }
+  inline double getTransformationEpsilon() { return (params_.trans_epsilon); }
 
-  inline void setMaximumIterations(int max_iterations)
-  {
-    params_.max_iterations = max_iterations;
-  }
-  inline int getMaxIterations() const
-  {
-    return params_.max_iterations;
-  }
+  inline void setMaximumIterations(int max_iterations) { params_.max_iterations = max_iterations; }
+  inline int getMaxIterations() const { return params_.max_iterations; }
 
-  void setParams(const NdtParams & ndt_params)
-  {
-    params_ = ndt_params;
-  }
+  void setParams(const NdtParams & ndt_params) { params_ = ndt_params; }
 
-  NdtParams getParams() const
-  {
-    return params_;
-  }
+  NdtParams getParams() const { return params_; }
 
 protected:
   using pcl::Registration<PointSource, PointTarget>::reg_name_;
diff --git a/include/pclomp/voxel_grid_covariance_omp.h b/include/pclomp/voxel_grid_covariance_omp.h
index b088fe6..373a52a 100644
--- a/include/pclomp/voxel_grid_covariance_omp.h
+++ b/include/pclomp/voxel_grid_covariance_omp.h
@@ -226,10 +226,7 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT>
   /** \brief Get the minimum number of points required for a cell to be used.
    * \return the minimum number of points for required for a voxel to be used
    */
-  inline int getMinPointPerVoxel()
-  {
-    return min_points_per_voxel_;
-  }
+  inline int getMinPointPerVoxel() { return min_points_per_voxel_; }
 
   /** \brief Set the minimum allowable ratio between eigenvalues to prevent singular covariance
    * matrices. \param[in] min_covar_eigvalue_mult the minimum allowable ratio between eigenvalues
@@ -242,10 +239,7 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT>
   /** \brief Get the minimum allowable ratio between eigenvalues to prevent singular covariance
    * matrices. \return the minimum allowable ratio between eigenvalues
    */
-  inline double getCovEigValueInflationRatio()
-  {
-    return min_covar_eigvalue_mult_;
-  }
+  inline double getCovEigValueInflationRatio() { return min_covar_eigvalue_mult_; }
 
   /** \brief Filter cloud and initializes voxel structure.
    * \param[out] output cloud containing centroids of voxels containing a sufficient number of
@@ -390,19 +384,13 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT>
   /** \brief Get the leaf structure map
    * \return a map containing all leaves
    */
-  inline const Map & getLeaves()
-  {
-    return leaves_;
-  }
+  inline const Map & getLeaves() { return leaves_; }
 
   /** \brief Get a pointcloud containing the voxel centroids
    * \note Only voxels containing a sufficient number of points are used.
    * \return a map containing all leaves
    */
-  inline PointCloudPtr getCentroids()
-  {
-    return voxel_centroids_;
-  }
+  inline PointCloudPtr getCentroids() { return voxel_centroids_; }
 
   /** \brief Get a cloud to visualize each voxels normal distribution.
    * \param[out] cell_cloud a cloud created by sampling the normal distributions of each voxel
diff --git a/include/pclomp/voxel_grid_covariance_omp_impl.hpp b/include/pclomp/voxel_grid_covariance_omp_impl.hpp
index 0a78ad5..5d0a843 100644
--- a/include/pclomp/voxel_grid_covariance_omp_impl.hpp
+++ b/include/pclomp/voxel_grid_covariance_omp_impl.hpp
@@ -197,7 +197,7 @@ void pclomp::VoxelGridCovariance<PointT>::applyFilter(PointCloud & output)
             sizeof(unsigned int));
           centroid[centroid_size - 3] = static_cast<float>((rgb >> 16u) & 0x0000ffu);
           centroid[centroid_size - 2] = static_cast<float>((rgb >> 8u) & 0x0000ffu);
-          centroid[centroid_size - 1] = static_cast<float>((rgb)&0x0000ffu);
+          centroid[centroid_size - 1] = static_cast<float>((rgb) & 0x0000ffu);
         }
         pcl::for_each_type<FieldList>(
           pcl::NdCopyPointEigenFunctor<PointT>(input_->points[cp], centroid));
@@ -253,7 +253,7 @@ void pclomp::VoxelGridCovariance<PointT>::applyFilter(PointCloud & output)
             &rgb, reinterpret_cast<const char *>(&input_->points[cp]) + rgba_index, sizeof(int));
           centroid[centroid_size - 3] = static_cast<float>((rgb >> 16u) & 0x0000ffu);
           centroid[centroid_size - 2] = static_cast<float>((rgb >> 8u) & 0x0000ffu);
-          centroid[centroid_size - 1] = static_cast<float>((rgb)&0x0000ffu);
+          centroid[centroid_size - 1] = static_cast<float>((rgb) & 0x0000ffu);
         }
         pcl::for_each_type<FieldList>(
           pcl::NdCopyPointEigenFunctor<PointT>(input_->points[cp], centroid));