37 #ifndef PCL_ROS_SHOT_H_    38 #define PCL_ROS_SHOT_H_    40 #include <pcl/features/shot.h>    51       pcl::SHOTEstimation<pcl::PointXYZ, pcl::Normal, pcl::SHOT352> 
impl_;
    74       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
    78 #endif  //#ifndef PCL_SHOT_H_ 
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method. 
pcl::IndicesPtr IndicesPtr
pcl::PointCloud< pcl::SHOT352 > PointCloudOut
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it. 
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type. 
pcl::SHOTEstimation< pcl::PointXYZ, pcl::Normal, pcl::SHOT352 > impl_
SHOTEstimation estimates SHOT descriptor. 
int max_queue_size_
The maximum queue size (default: 3). 
ros::Publisher pub_output_
The output PointCloud publisher.