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