Template Class LocalPlaneSacModel
Defined in File LocalPlaneSacModel.h
Inheritance Relationships
Base Type
public pcl::SampleConsensusModelPlane< PointT >
Class Documentation
-
template<typename PointT>
class LocalPlaneSacModel : public pcl::SampleConsensusModelPlane<PointT> PCL sample consensus model of a local surface plane with a location and a radius.
The model coefficients are defined as:
normal_x : the X coordinate of the plane’s normal vector (normalized)
normal_y : the Y coordinate of the plane’s normal vector (normalized)
normal_z : the Z coordinate of the plane’s normal vector (normalized)
d : the fourth Hessian component of the board’s equation
center_x : the X coordinate of the plane’s center
center_y : the Y coordinate of the plane’s center
center_z : the Z coordinate of the plane’s center
radius : the radius of the local plane
When used within the RANSAC algorithm of the PCL, the inliers are chosen not only based on the distance with respect to the plane, if it lies within the given radius to the center point.
Public Types
-
using Ptr = pcl::shared_ptr<LocalPlaneSacModel<PointT>>
-
using ConstPtr = pcl::shared_ptr<const LocalPlaneSacModel<PointT>>
Public Functions
-
LocalPlaneSacModel(const PointCloudConstPtr &cloud, bool random = false)
Constructor for base LocalPlaneSacModel.
- Parameters:
cloud – [in] the input point cloud dataset
random – [in] if true set the random seed to the current time, else set to 12345 (default: false)
-
LocalPlaneSacModel(const PointCloudConstPtr &cloud, const std::vector<int> &indices, bool random = false)
Constructor for base LocalPlaneSacModel.
- Parameters:
cloud – [in] the input point cloud dataset
indices – [in] a vector of point indices to be used from cloud
random – [in] if true set the random seed to the current time, else set to 12345 (default: false)
-
~LocalPlaneSacModel()
Empty destructor.
-
void clearIndices()
Clear list of indices.
-
void setCenter(const Eigen::Vector3f &iCenter)
Method to set center of local plane as seen from the sensors coordinate system.
- Parameters:
iCenter – [in] Translational vector as seen from the reference coordinate system.
-
void setRadius(const float &iRadius)
Method to set radius of local plane.
- Parameters:
iRadius – [in] Value of radius to set.
-
void setIncrementalCenterUpdate(const bool iValue)
Method to set incremental center update.
If set to true, this will allow the model to keep track of the number of inliers and update the center point each time the number of inlier increases.
-
void setTranslationVariance(const double iValue)
Set the shift value (with respect to the pose guess) with which different positions of the target should be testet.
- Parameters:
iValue – Value in meters.
-
bool computeModelCoefficients(const std::vector<int> &samples, Eigen::VectorXf &model_coefficients) const override
Check whether the given index samples can form a valid plane model, compute the model coefficients from these samples and store them internally in model_coefficients_. The plane coefficients are: a, b, c, d (ax+by+cz+d=0)
- Parameters:
samples – [in] the point indices found as possible good candidates for creating a valid model
model_coefficients – [out] the resultant model coefficients
-
void selectWithinDistance(const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers) override
Select all the points which respect the given model coefficients as inliers.
- Parameters:
model_coefficients – [in] the coefficients of a plane model that we need to compute distances to
threshold – [in] a maximum admissible distance threshold for determining the inliers from the outliers
inliers – [out] the resultant model inliers
-
std::size_t countWithinDistance(const Eigen::VectorXf &model_coefficients, const double threshold) const override
Count all the points which respect the given model coefficients as inliers.
- Parameters:
model_coefficients – [in] the coefficients of a model that we need to compute distances to
threshold – [in] maximum admissible distance threshold for determining the inliers from the outliers
- Returns:
the resultant number of inliers
-
void optimizeModelCoefficients(const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) const override
Recompute the plane coefficients using the given inlier set and return them to the user.
Note
: these are the coefficients of the plane model after refinement (e.g. after SVD)
- Parameters:
inliers – [in] the data inliers found as supporting the model
model_coefficients – [in] the initial guess for the model coefficients
optimized_coefficients – [out] the resultant recomputed coefficients after non-linear optimization
-
void setInputCloud(const PointCloudConstPtr &cloud) override
Provide a pointer to the input dataset. This will first clear the list of indices.
- Parameters:
cloud – [in] the const boost shared pointer to a PointCloud message
Protected Functions
-
bool isModelValid(const Eigen::VectorXf &model_coefficients) const override
Check whether a model is valid given the user constraints.
- Parameters:
model_coefficients – [in] the set of model coefficients