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 getHessian() const - { - return hessian_; - } + inline Eigen::Matrix getHessian() const { return hessian_; } /** \brief Return the transformation array */ inline const std::vector> & @@ -305,10 +273,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration getVoxelPCD() const - { - return target_cells_.getVoxelPCD(); - } + pcl::PointCloud getVoxelPCD() const { return target_cells_.getVoxelPCD(); } - std::vector getCurrentMapIDs() const - { - return target_cells_.getCurrentMapIDs(); - } + std::vector getCurrentMapIDs() const { return target_cells_.getCurrentMapIDs(); } protected: using BaseRegType::converged_; @@ -413,9 +357,7 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration getHessian() const - { - return hessian_; - } + inline Eigen::Matrix getHessian() const { return hessian_; } /** \brief Return the transformation array */ inline const std::vector> & @@ -257,30 +222,15 @@ class NormalDistributionsTransform : public pcl::Registration getScores() const - { - return scores_; - } + inline const std::vector getScores() const { return scores_; } - inline const TargetGrid getTargetCells() const - { - return target_cells_; - } + inline const TargetGrid getTargetCells() const { return target_cells_; } - inline const std::map getScoreMap() const - { - return voxel_score_map_; - } + inline const std::map getScoreMap() const { return voxel_score_map_; } - inline const std::map getNoPointMap() const - { - return nomap_points_num_; - } + inline const std::map getNoPointMap() const { return nomap_points_num_; } - std::set & getEmptyVoxels() - { - return empty_voxels_; - } + std::set & getEmptyVoxels() { return empty_voxels_; } // For debug void cleanScores() @@ -306,10 +256,7 @@ class NormalDistributionsTransform : public pcl::Registration::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 /** \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 /** \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 /** \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::applyFilter(PointCloud & output) sizeof(unsigned int)); centroid[centroid_size - 3] = static_cast((rgb >> 16u) & 0x0000ffu); centroid[centroid_size - 2] = static_cast((rgb >> 8u) & 0x0000ffu); - centroid[centroid_size - 1] = static_cast((rgb)&0x0000ffu); + centroid[centroid_size - 1] = static_cast((rgb) & 0x0000ffu); } pcl::for_each_type( pcl::NdCopyPointEigenFunctor(input_->points[cp], centroid)); @@ -253,7 +253,7 @@ void pclomp::VoxelGridCovariance::applyFilter(PointCloud & output) &rgb, reinterpret_cast(&input_->points[cp]) + rgba_index, sizeof(int)); centroid[centroid_size - 3] = static_cast((rgb >> 16u) & 0x0000ffu); centroid[centroid_size - 2] = static_cast((rgb >> 8u) & 0x0000ffu); - centroid[centroid_size - 1] = static_cast((rgb)&0x0000ffu); + centroid[centroid_size - 1] = static_cast((rgb) & 0x0000ffu); } pcl::for_each_type( pcl::NdCopyPointEigenFunctor(input_->points[cp], centroid));