MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point. More...
#include <moment_invariants.h>

Public Types | |
| typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
| void | computePointMomentInvariants (const pcl::PointCloud< PointInT > &cloud, float &j1, float &j2, float &j3) |
| Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices. | |
| void | computePointMomentInvariants (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, float &j1, float &j2, float &j3) |
| Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices. | |
| MomentInvariantsEstimation () | |
| Empty constructor. | |
Protected Member Functions | |
| void | computeFeature (PointCloudOut &output) |
| Estimate moment invariants for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod (). | |
Private Attributes | |
| Eigen::Vector4f | temp_pt_ |
| Internal data vector. | |
| Eigen::Vector4f | xyz_centroid_ |
| 16-bytes aligned placeholder for the XYZ centroid of a surface patch. | |
MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point.
Definition at line 53 of file moment_invariants.h.
| typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::MomentInvariantsEstimation< PointInT, PointOutT >::PointCloudOut |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
Definition at line 63 of file moment_invariants.h.
| pcl::MomentInvariantsEstimation< PointInT, PointOutT >::MomentInvariantsEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 67 of file moment_invariants.h.
| void pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [inline, protected, virtual] |
Estimate moment invariants for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ().
| output | the resultant point cloud model dataset that contains the moment invariants |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 112 of file moment_invariants.hpp.
| void pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computePointMomentInvariants | ( | const pcl::PointCloud< PointInT > & | cloud, | |
| float & | j1, | |||
| float & | j2, | |||
| float & | j3 | |||
| ) | [inline] |
Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices.
| cloud | the input point cloud | |
| j1 | the resultant first moment invariant | |
| j2 | the resultant second moment invariant | |
| j3 | the resultant third moment invariant |
Definition at line 79 of file moment_invariants.hpp.
| void pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computePointMomentInvariants | ( | const pcl::PointCloud< PointInT > & | cloud, | |
| const std::vector< int > & | indices, | |||
| float & | j1, | |||
| float & | j2, | |||
| float & | j3 | |||
| ) | [inline] |
Compute the 3 moment invariants (j1, j2, j3) for a given set of points, using their indices.
| cloud | the input point cloud | |
| indices | the point cloud indices that need to be used | |
| j1 | the resultant first moment invariant | |
| j2 | the resultant second moment invariant | |
| j3 | the resultant third moment invariant |
Definition at line 45 of file moment_invariants.hpp.
Eigen::Vector4f pcl::MomentInvariantsEstimation< PointInT, PointOutT >::temp_pt_ [private] |
Internal data vector.
Definition at line 105 of file moment_invariants.h.
Eigen::Vector4f pcl::MomentInvariantsEstimation< PointInT, PointOutT >::xyz_centroid_ [private] |
16-bytes aligned placeholder for the XYZ centroid of a surface patch.
Definition at line 102 of file moment_invariants.h.