A comparison whether the (x,y,z) components of a given point satisfy (p'Ap + 2v'p + c [OP] 0). Here [OP] stands for the defined pcl::ComparisonOps, i.e. for GT, GE, LT, LE or EQ; p = (x,y,z) is a point of the point cloud; A is 3x3 matrix; v is the 3x1 vector; c is a scalar. More...
#include <conditional_removal.h>
Public Types | |
typedef boost::shared_ptr < const TfQuadraticXYZComparison < PointT > > | ConstPtr |
Public Member Functions | |
virtual bool | evaluate (const PointT &point) const |
Determine the result of this comparison. | |
void | setComparisonMatrix (const Eigen::Matrix3f &matrix) |
set the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0". | |
void | setComparisonMatrix (const Eigen::Matrix4f &homogeneousMatrix) |
set the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0". | |
void | setComparisonOperator (const pcl::ComparisonOps::CompareOp op) |
set the operator "[OP]" of the comparison "p'Ap + 2v'p + c [OP] 0". | |
void | setComparisonScalar (const float &scalar) |
set the scalar "c" of the comparison "p'Ap + 2v'p + c [OP] 0". | |
void | setComparisonVector (const Eigen::Vector3f &vector) |
set the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0". | |
void | setComparisonVector (const Eigen::Vector4f &homogeneousVector) |
set the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0". | |
TfQuadraticXYZComparison () | |
Constructor. | |
TfQuadraticXYZComparison (const pcl::ComparisonOps::CompareOp op, const Eigen::Matrix3f &comparison_matrix, const Eigen::Vector3f &comparison_vector, const float &comparison_scalar, const Eigen::Affine3f &comparison_transform=Eigen::Affine3f::Identity()) | |
Constructor. | |
void | transformComparison (const Eigen::Matrix4f &transform) |
transform the coordinate system of the comparison. If you think of the transformation to be a translation and rotation of the comparison in the same coordinate system, you have to provide the inverse transformation. This function does not change the original definition of the comparison. Thus, each call of this function will assume the original definition of the comparison as starting point for the transformation. | |
void | transformComparison (const Eigen::Affine3f &transform) |
transform the coordinate system of the comparison. If you think of the transformation to be a translation and rotation of the comparison in the same coordinate system, you have to provide the inverse transformation. This function does not change the original definition of the comparison. Thus, each call of this function will assume the original definition of the comparison as starting point for the transformation. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr < TfQuadraticXYZComparison < PointT > > | Ptr |
Protected Attributes | |
Eigen::Matrix4f | comp_matr_ |
float | comp_scalar_ |
Eigen::Vector4f | comp_vect_ |
Private Attributes | |
Eigen::Matrix4f | tf_comp_matr_ |
Eigen::Vector4f | tf_comp_vect_ |
A comparison whether the (x,y,z) components of a given point satisfy (p'Ap + 2v'p + c [OP] 0). Here [OP] stands for the defined pcl::ComparisonOps, i.e. for GT, GE, LT, LE or EQ; p = (x,y,z) is a point of the point cloud; A is 3x3 matrix; v is the 3x1 vector; c is a scalar.
Definition at line 293 of file conditional_removal.h.
typedef boost::shared_ptr<const TfQuadraticXYZComparison<PointT> > pcl::TfQuadraticXYZComparison< PointT >::ConstPtr |
Reimplemented from pcl::ComparisonBase< PointT >.
Definition at line 299 of file conditional_removal.h.
pcl::TfQuadraticXYZComparison< PointT >::TfQuadraticXYZComparison | ( | ) |
Constructor.
Definition at line 382 of file conditional_removal.hpp.
pcl::TfQuadraticXYZComparison< PointT >::TfQuadraticXYZComparison | ( | const pcl::ComparisonOps::CompareOp | op, |
const Eigen::Matrix3f & | comparison_matrix, | ||
const Eigen::Vector3f & | comparison_vector, | ||
const float & | comparison_scalar, | ||
const Eigen::Affine3f & | comparison_transform = Eigen::Affine3f::Identity () |
||
) |
Constructor.
op | the operator "[OP]" of the comparison "p'Ap + 2v'p + c [OP] 0". |
comparison_matrix | the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0". |
comparison_vector | the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0". |
comparison_scalar | the scalar "c" of the comparison "p'Ap + 2v'p + c [OP] 0". |
comparison_transform | the transformation of the comparison. |
Definition at line 443 of file conditional_removal.hpp.
bool pcl::TfQuadraticXYZComparison< PointT >::evaluate | ( | const PointT & | point | ) | const [virtual] |
Determine the result of this comparison.
point | the point to evaluate |
Implements pcl::ComparisonBase< PointT >.
Definition at line 509 of file conditional_removal.hpp.
void pcl::TfQuadraticXYZComparison< PointT >::setComparisonMatrix | ( | const Eigen::Matrix3f & | matrix | ) | [inline] |
set the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0".
Definition at line 327 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::setComparisonMatrix | ( | const Eigen::Matrix4f & | homogeneousMatrix | ) | [inline] |
set the matrix "A" of the comparison "p'Ap + 2v'p + c [OP] 0".
Definition at line 339 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::setComparisonOperator | ( | const pcl::ComparisonOps::CompareOp | op | ) | [inline] |
set the operator "[OP]" of the comparison "p'Ap + 2v'p + c [OP] 0".
Definition at line 319 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::setComparisonScalar | ( | const float & | scalar | ) | [inline] |
set the scalar "c" of the comparison "p'Ap + 2v'p + c [OP] 0".
Definition at line 366 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::setComparisonVector | ( | const Eigen::Vector3f & | vector | ) | [inline] |
set the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0".
Definition at line 348 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::setComparisonVector | ( | const Eigen::Vector4f & | homogeneousVector | ) | [inline] |
set the vector "v" of the comparison "p'Ap + 2v'p + c [OP] 0".
Definition at line 357 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::transformComparison | ( | const Eigen::Matrix4f & | transform | ) | [inline] |
transform the coordinate system of the comparison. If you think of the transformation to be a translation and rotation of the comparison in the same coordinate system, you have to provide the inverse transformation. This function does not change the original definition of the comparison. Thus, each call of this function will assume the original definition of the comparison as starting point for the transformation.
transform | the transformation (rotation and translation) as an affine matrix. |
Definition at line 381 of file conditional_removal.h.
void pcl::TfQuadraticXYZComparison< PointT >::transformComparison | ( | const Eigen::Affine3f & | transform | ) | [inline] |
transform the coordinate system of the comparison. If you think of the transformation to be a translation and rotation of the comparison in the same coordinate system, you have to provide the inverse transformation. This function does not change the original definition of the comparison. Thus, each call of this function will assume the original definition of the comparison as starting point for the transformation.
transform | the transformation (rotation and translation) as an affine matrix. |
Definition at line 397 of file conditional_removal.h.
Eigen::Matrix4f pcl::TfQuadraticXYZComparison< PointT >::comp_matr_ [protected] |
Definition at line 413 of file conditional_removal.h.
float pcl::TfQuadraticXYZComparison< PointT >::comp_scalar_ [protected] |
Definition at line 416 of file conditional_removal.h.
Eigen::Vector4f pcl::TfQuadraticXYZComparison< PointT >::comp_vect_ [protected] |
Definition at line 414 of file conditional_removal.h.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr<TfQuadraticXYZComparison<PointT> > pcl::TfQuadraticXYZComparison< PointT >::Ptr |
Reimplemented from pcl::ComparisonBase< PointT >.
Definition at line 298 of file conditional_removal.h.
Eigen::Matrix4f pcl::TfQuadraticXYZComparison< PointT >::tf_comp_matr_ [private] |
Definition at line 419 of file conditional_removal.h.
Eigen::Vector4f pcl::TfQuadraticXYZComparison< PointT >::tf_comp_vect_ [private] |
Definition at line 420 of file conditional_removal.h.