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

Private Types | |
| typedef pcl::PointCloud < pcl::MomentInvariants > | PointCloudOut |
Private Member Functions | |
| bool | childInit (ros::NodeHandle &nh) |
| Child initialization routine. Internal method. | |
| void | computePublish (const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesConstPtr &indices) |
| Compute the feature and publish it. | |
| void | emptyPublish (const PointCloudInConstPtr &cloud) |
| Publish an empty point cloud of the feature output type. | |
Private Attributes | |
| pcl::MomentInvariantsEstimation < pcl::PointXYZ, pcl::MomentInvariants > | impl_ |
MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point.
Definition at line 49 of file moment_invariants.h.
typedef pcl::PointCloud<pcl::MomentInvariants> pcl_ros::MomentInvariantsEstimation::PointCloudOut [private] |
Definition at line 46 of file moment_invariants.h.
| bool pcl_ros::MomentInvariantsEstimation::childInit | ( | ros::NodeHandle & | nh | ) | [inline, private, virtual] |
Child initialization routine. Internal method.
Implements pcl_ros::Feature.
Definition at line 50 of file moment_invariants.h.
| void pcl_ros::MomentInvariantsEstimation::computePublish | ( | const PointCloudInConstPtr & | cloud, | |
| const PointCloudInConstPtr & | surface, | |||
| const IndicesConstPtr & | indices | |||
| ) | [private, virtual] |
Compute the feature and publish it.
Implements pcl_ros::Feature.
Definition at line 50 of file moment_invariants.cpp.
| void pcl_ros::MomentInvariantsEstimation::emptyPublish | ( | const PointCloudInConstPtr & | cloud | ) | [private, virtual] |
Publish an empty point cloud of the feature output type.
Implements pcl_ros::Feature.
Definition at line 42 of file moment_invariants.cpp.
pcl::MomentInvariantsEstimation<pcl::PointXYZ, pcl::MomentInvariants> pcl_ros::MomentInvariantsEstimation::impl_ [private] |
Definition at line 44 of file moment_invariants.h.