Skip to content

Commit

Permalink
fix(autoware_ndt_scan_matcher): remove unsed functions
Browse files Browse the repository at this point in the history
Signed-off-by: Ryuta Kambe <ryuta.kambe@tier4.jp>
  • Loading branch information
veqcc committed Nov 19, 2024
1 parent 5778e01 commit a0b4896
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 94 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -171,12 +171,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid<PointT>
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
*/
Expand All @@ -191,11 +185,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid<PointT>

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_;

Expand Down Expand Up @@ -351,15 +340,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid<PointT>
}
}

// A wrapper of the real apply_filter
inline bool apply_filter_thread(int tid, GridNodeType & node)
{
apply_filter(processing_inputs_[tid], node);
processing_inputs_[tid].reset();

return true;
}

/** \brief Filter cloud and initializes voxel structure.
* \param[out] output cloud containing centroids of voxels containing a sufficient number of
* points
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,15 +132,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
/** \brief Empty destructor */
virtual ~MultiGridNormalDistributionsTransform() {}

void setNumThreads(int n)
{
params_.num_threads = n;

target_cells_.setThreadNum(params_.num_threads);
}

inline int getNumThreads() const { return params_.num_threads; }

inline void setInputSource(const PointCloudSourceConstPtr & input)
{
// This is to avoid segmentation fault when setting null input
Expand Down Expand Up @@ -178,43 +169,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
target_cloud_updated_ = false;
}

/** \brief Set/change the voxel grid resolution.
* \param[in] resolution side length of voxels
*/
inline void setResolution(float resolution)
{
// Prevents unnecessary voxel initiations
if (params_.resolution != resolution) {
params_.resolution = resolution;
if (input_) init();
}
}

/** \brief Get voxel grid resolution.
* \return side length of voxels
*/
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); }

/** \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; }

/** \brief Get the point cloud outlier ratio.
* \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; }

/** \brief Get the registration alignment probability.
* \return transformation probability
*/
Expand Down Expand Up @@ -271,11 +225,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
pcl::PointCloud<pcl::PointXYZI> 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;
Expand All @@ -298,29 +247,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration<PointSour
return ndt_result;
}

/** \brief Set the transformation epsilon (maximum allowable translation squared
* difference between two consecutive transformations) in order for an optimization to
* be considered as having converged to the final solution. \param[in] epsilon the
* 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; }

/** \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 void setMaximumIterations(int max_iterations)
{
params_.max_iterations = max_iterations;
max_iterations_ = params_.max_iterations;
}

inline int getMaxIterations() const { return params_.max_iterations; }

inline int getMaxIterations() { return params_.max_iterations; }

void setParams(const NdtParams & ndt_params)
{
params_ = ndt_params;
Expand Down

0 comments on commit a0b4896

Please sign in to comment.