Public Member Functions |
void | findTaubinNormalAxis (const std::vector< int > &indices, const Eigen::VectorXi &cam_source) |
| Estimate the local axes for the quadric fitted to the point neighborhood.
|
void | fitQuadric (const std::vector< int > &indices) |
| Fit a quadratic surface to a point neighborhood.
|
const Eigen::Vector3d & | getBinormal () const |
| Return the binormal for the quadric fitted to the point neighborhood.
|
const Eigen::Vector3d & | getCurvatureAxis () const |
| Return the curvature axis for the quadric fitted to the point neighborhood.
|
const Eigen::Vector3d & | getNormal () const |
| Return the normal for the quadric fitted to the point neighborhood.
|
const Eigen::Vector3d & | getSample () const |
| Return the sample for which the point neighborhood was found.
|
void | plotAxes (void *viewer_void, int id) const |
| Plot the local axes.
|
void | print () |
| Print a description of the quadric to the system's standard output.
|
| Quadric () |
| Standard constructor.
|
| Quadric (const std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > &T_cams, const PointCloud::Ptr &input, const Eigen::Vector3d &sample, bool is_deterministic) |
| Constructor.
|
void | setInputCloud (const PointCloud::Ptr &input) |
| Set the input point cloud.
|
Private Member Functions |
void | findAverageNormalAxis (const Eigen::MatrixXd &normals) |
| Estimate the average normal axis for the quadric fitted to the point neighborhood.
|
bool | solveGeneralizedEigenProblem (const Eigen::MatrixXd &A, const Eigen::MatrixXd &B, Eigen::MatrixXd &v, Eigen::MatrixXd &lambda) |
| Solve the generalized Eigen problem A * v(j) = lambda(j) * B * v(j), where v are the Eigen vectors, and lambda are the Eigen values. The eigenvalues are stored as: (lambda(:, 1) + lambda(:, 2)*i)./lambda(:, 3). This method returns true if the Eigen problem is solved successfully.
|
void | unpackQuadric () |
| Unpack the parameters of the quadric.
|
Private Attributes |
Eigen::Vector3d | binormal_ |
| the curvature, normal, and binormal axis
|
Eigen::Matrix3Xd | cam_origins_ |
| the camera positions
|
Eigen::Vector3d | centroid_ |
| the centroid of the quadric
|
Eigen::Matrix3d | covariance_matrix_ |
| the covariance matrix of the quadric
|
Eigen::Vector3d | curvature_axis_ |
PointCloud::Ptr | input_ |
| the input point cloud
|
bool | is_deterministic_ |
| whether the local axes estimation is deterministic
|
int | majority_cam_source_ |
| the majority camera source
|
Eigen::Vector3d | normal_ |
double | normals_ratio_ |
| the ratio between the normals of the quadric
|
Eigen::Matrix< double, 10, 1 > | parameters_ |
| the parameters of the quadric (implicit form)
|
Eigen::Vector3d | sample_ |
| the sample for which the point neighborhood was found
|
Static Private Attributes |
static const int | TAUBIN_MATRICES_SIZE = 10 |
| size of matrices in Taubin Quadric Fitting
|
Quadratic surface fit and local axes estimation.
Quadric class
This class fits a quadratic surface to a point neighborhood and estimates the curvature axis, normal, and binormal for the surface fitted to a point neighborhood. To fit the quadratic surface, a method from the LAPACK library is used.
Definition at line 60 of file quadric.h.
Solve the generalized Eigen problem A * v(j) = lambda(j) * B * v(j), where v are the Eigen vectors, and lambda are the Eigen values. The eigenvalues are stored as: (lambda(:, 1) + lambda(:, 2)*i)./lambda(:, 3). This method returns true if the Eigen problem is solved successfully.
- Parameters:
-
A | the matrix A in the problem |
B | the matrix B in the problem |
v | the resultant Eigen vectors |
lambda | the resultant Eigen vectors (see above) |
- Returns:
- true if the solution process worked properly, false otherwise
Definition at line 330 of file quadric.cpp.