Template Class EmptyCircle3DSacModel
Defined in File EmptyCircle3DSacModel.hpp
Inheritance Relationships
Base Type
public pcl::SampleConsensusModelCircle3D< PointT >
Class Documentation
-
template<typename PointT>
class EmptyCircle3DSacModel : public pcl::SampleConsensusModelCircle3D<PointT> EmptyCircle3DSacModel defines a pcl sample consensus model of an empty planar circle.
The model coefficients are defined as:
center_x : the X coordinate of the circles’ center point
center_y : the Y coordinate of the circles’ center point
center_z : the Z coordinate of the circles’ center point
radius : the radius of the circle
normal_x : the X coordinate of the circles’ normal vector (normalized)
normal_y : the Y coordinate of the circles’ normal vector (normalized)
normal_z : the Z coordinate of the circles’ normal vector (normalized)
Public Types
-
using Ptr = pcl::shared_ptr<EmptyCircle3DSacModel<PointT>>
-
using ConstPtr = pcl::shared_ptr<const EmptyCircle3DSacModel<PointT>>
Public Functions
-
inline EmptyCircle3DSacModel(const PointCloudConstPtr &cloud, bool random = false)
Constructor for base EmptyCircle3DSacModel.
- 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)
-
inline EmptyCircle3DSacModel(const PointCloudConstPtr &cloud, const std::vector<int> &indices, bool random = false)
Constructor for base SampleConsensusModelEmptyCircle3D.
- 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)
-
inline ~EmptyCircle3DSacModel()
Empty destructor.
-
inline void setAxis(const Eigen::Vector3f &ax)
Set the axis along which we need to search for a circle normal.
- Parameters:
ax – [in] the axis
-
inline Eigen::Vector3f getAxis() const
Get the axis along which we need to search for a circle normal.
-
inline void setEpsAngle(const double ea)
Set the angle epsilon (delta) threshold.
Note
You need to specify an angle > 0 in order to activate the axis-angle constraint!
- Parameters:
ea – [in] the maximum allowed difference (in degrees) between the plane normal and the given axis.
-
inline double getEpsAngle() const
Get the angle epsilon (in degrees) threshold.
-
inline void setExpectedPointDensity(const float &iExpectedDensity)
Set the point density expected of the point cloud in which the target is to be detected.
Note
Density needs to be greater than 0
-
inline void setSupportRegionLimits(const float &iMinSupportRadius, const float &iMaxSupportRadius)
Set the limits (min and max radius) of the support region.
Note
Both radii need to be greater than 0 and the max radius needs to be larger to min radius.
-
inline void addInvalidParameterization(const Eigen::VectorXf &newInvalidParameterization)
Method to add a parameterization that is to be considered as invalid.
- Parameters:
newInvalidParameterization – [in] parameterization as center and radius in the same order as stored in the model coefficients.
-
inline bool isSampleGood(const std::vector<int> &samples) const
Method to check whether given samples are good.
This checks that all enclosed angle of the triangle with these three points are greater than 30°.
-
inline std::size_t countWithinDistance(const Eigen::VectorXf &modelCoefficients, const double threshold) const override
Count all the points which respect the given model coefficients as inliers.
- Parameters:
modelCoefficients – [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
-
inline void selectWithinDistance(const Eigen::VectorXf &modelCoefficients, const double threshold, std::vector<int> &inliers) override
Select all the points which respect the given model coefficients as inliers.
- Parameters:
modelCoefficients – [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
inliers – [in]
- Returns:
the resultant number of inliers
-
inline float getScore(const int &iNumInliers) const
Get score for a given amount of inliers.
The score is the ratio between the given number of inliers and the expected number of inliers based on size of the support region, defined by the maximum support radius
Protected Functions
-
inline bool isModelValid(const Eigen::VectorXf &modelCoefficients) const override
Check whether a model is valid given the user constraints.
- Parameters:
modelCoefficients – [in] the set of model coefficients
-
inline float calculateCircleArea(const float &iRadius) const
Compute area of a circle with given radius.