diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h index 0e43b0b35aecd..35451ede3a6aa 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h @@ -171,12 +171,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid return *this; } - /** \brief Get the voxel covariance. - * \return covariance matrix - */ - const Eigen::Matrix3d & getCov() const { return (cov_); } - Eigen::Matrix3d & getCov() { return (cov_); } - /** \brief Get the inverse of the voxel covariance. * \return inverse covariance matrix */ @@ -191,11 +185,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid Eigen::Vector3d & getMean() { return (mean_); } - /** \brief Get the number of points contained by this voxel. - * \return number of points - */ - int getPointCount() const { return (nr_points_); } - /** \brief Number of points contained by voxel */ int nr_points_; @@ -352,6 +341,7 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid } // A wrapper of the real apply_filter + // cppcheck-suppress unusedFunction inline bool apply_filter_thread(int tid, GridNodeType & node) { apply_filter(processing_inputs_[tid], node); diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h index b173d164de97d..00c567775a6bf 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h @@ -132,15 +132,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration calculateNearestVoxelScoreEachPoint( const PointCloudSource & cloud) const; - inline void setRegularizationScaleFactor(float regularization_scale_factor) - { - params_.regularization_scale_factor = regularization_scale_factor; - } - inline void setRegularizationPose(Eigen::Matrix4f regularization_pose) { regularization_pose_ = regularization_pose; @@ -298,29 +247,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration