38 #ifndef PCL_ROS_NORMAL_3D_OMP_H_ 39 #define PCL_ROS_NORMAL_3D_OMP_H_ 41 #include <pcl/features/normal_3d_omp.h> 53 pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal>
impl_;
75 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
79 #endif //#ifndef PCL_ROS_NORMAL_3D_OMP_H_
pcl::IndicesPtr IndicesPtr
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and ...
pcl::NormalEstimationOMP< pcl::PointXYZ, pcl::Normal > impl_
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl::PointCloud< pcl::Normal > PointCloudOut
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.