38 #ifndef PCL_ROS_MOMENT_INVARIANTS_H_ 39 #define PCL_ROS_MOMENT_INVARIANTS_H_ 41 #include <pcl/features/moment_invariants.h> 55 pcl::MomentInvariantsEstimation<pcl::PointXYZ, pcl::MomentInvariants>
impl_;
77 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
81 #endif //#ifndef PCL_ROS_MOMENT_INVARIANTS_H_
pcl::PointCloud< pcl::MomentInvariants > PointCloudOut
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point...
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
pcl::MomentInvariantsEstimation< pcl::PointXYZ, pcl::MomentInvariants > impl_