Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
Quadric Class Reference

Quadratic surface fit and local axes estimation. More...

#include <quadric.h>

List of all members.

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 pcl::PointCloud< pcl::PointXYZ >::Ptr &input, const Eigen::Vector3d &sample, bool is_deterministic)
 Constructor.
void setInputCloud (const pcl::PointCloud< pcl::PointXYZ >::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_
pcl::PointCloud< pcl::PointXYZ >
::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

Detailed Description

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 55 of file quadric.h.


Constructor & Destructor Documentation

Quadric::Quadric ( ) [inline]

Standard constructor.

Definition at line 62 of file quadric.h.

Quadric::Quadric ( const std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > &  T_cams,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  input,
const Eigen::Vector3d &  sample,
bool  is_deterministic 
)

Constructor.

Parameters:
T_camsthe camera poses
inputthe input point cloud
samplethe sample for which the point neighborhood was found
is_deterministic_whether the local axes estimation is deterministic

Definition at line 3 of file quadric.cpp.


Member Function Documentation

void Quadric::findAverageNormalAxis ( const Eigen::MatrixXd &  normals) [private]

Estimate the average normal axis for the quadric fitted to the point neighborhood.

Parameters:
normalsthe 3xn matrix of normals found for points in the point neighborhood

Definition at line 263 of file quadric.cpp.

void Quadric::findTaubinNormalAxis ( const std::vector< int > &  indices,
const Eigen::VectorXi &  cam_source 
)

Estimate the local axes for the quadric fitted to the point neighborhood.

Parameters:
indicesthe list of point cloud indices that belong to the point neighborhood
cam_sourcethe camera source for each point in the point cloud

Definition at line 159 of file quadric.cpp.

void Quadric::fitQuadric ( const std::vector< int > &  indices)

Fit a quadratic surface to a point neighborhood.

Parameters:
indicesthe list of point cloud indices that belong to the point neighborhood

Definition at line 14 of file quadric.cpp.

const Eigen::Vector3d& Quadric::getBinormal ( ) const [inline]

Return the binormal for the quadric fitted to the point neighborhood.

Returns:
the 3x1 binormal for the quadric fitted to the point neighborhood

Definition at line 123 of file quadric.h.

const Eigen::Vector3d& Quadric::getCurvatureAxis ( ) const [inline]

Return the curvature axis for the quadric fitted to the point neighborhood.

Returns:
the 3x1 curvature axis for the quadric fitted to the point neighborhood

Definition at line 132 of file quadric.h.

const Eigen::Vector3d& Quadric::getNormal ( ) const [inline]

Return the normal for the quadric fitted to the point neighborhood.

Returns:
the 3x1 normal for the quadric fitted to the point neighborhood

Definition at line 141 of file quadric.h.

const Eigen::Vector3d& Quadric::getSample ( ) const [inline]

Return the sample for which the point neighborhood was found.

Returns:
the 3x1 sample for which the point neighborhood was found

Definition at line 114 of file quadric.h.

void Quadric::plotAxes ( void *  viewer_void,
int  id 
) const

Plot the local axes.

Parameters:
viewer_voida pointer to a PCL visualizer
idan identifier number for the axes

Definition at line 365 of file quadric.cpp.

void Quadric::print ( )

Print a description of the quadric to the system's standard output.

Definition at line 253 of file quadric.cpp.

void Quadric::setInputCloud ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  input) [inline]

Set the input point cloud.

Parameters:
inputthe input point cloud

Definition at line 93 of file quadric.h.

bool Quadric::solveGeneralizedEigenProblem ( const Eigen::MatrixXd &  A,
const Eigen::MatrixXd &  B,
Eigen::MatrixXd &  v,
Eigen::MatrixXd &  lambda 
) [private]

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:
Athe matrix A in the problem
Bthe matrix B in the problem
vthe resultant Eigen vectors
lambdathe resultant Eigen vectors (see above)
Returns:
true if the solution process worked properly, false otherwise

Definition at line 330 of file quadric.cpp.

void Quadric::unpackQuadric ( ) [private]

Unpack the parameters of the quadric.

Definition at line 307 of file quadric.cpp.


Member Data Documentation

Eigen::Vector3d Quadric::binormal_ [private]

the curvature, normal, and binormal axis

Definition at line 178 of file quadric.h.

Eigen::Matrix3Xd Quadric::cam_origins_ [private]

the camera positions

Definition at line 174 of file quadric.h.

Eigen::Vector3d Quadric::centroid_ [private]

the centroid of the quadric

Definition at line 180 of file quadric.h.

Eigen::Matrix3d Quadric::covariance_matrix_ [private]

the covariance matrix of the quadric

Definition at line 181 of file quadric.h.

Eigen::Vector3d Quadric::curvature_axis_ [private]

Definition at line 178 of file quadric.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr Quadric::input_ [private]

the input point cloud

Definition at line 177 of file quadric.h.

whether the local axes estimation is deterministic

Definition at line 173 of file quadric.h.

the majority camera source

Definition at line 176 of file quadric.h.

Eigen::Vector3d Quadric::normal_ [private]

Definition at line 178 of file quadric.h.

double Quadric::normals_ratio_ [private]

the ratio between the normals of the quadric

Definition at line 182 of file quadric.h.

Eigen::Matrix<double, 10, 1> Quadric::parameters_ [private]

the parameters of the quadric (implicit form)

Definition at line 179 of file quadric.h.

Eigen::Vector3d Quadric::sample_ [private]

the sample for which the point neighborhood was found

Definition at line 175 of file quadric.h.

const int Quadric::TAUBIN_MATRICES_SIZE = 10 [static, private]

size of matrices in Taubin Quadric Fitting

Definition at line 184 of file quadric.h.


The documentation for this class was generated from the following files:


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28