Go to the documentation of this file.
38 #ifndef PCL_ROS_NORMAL_3D_TBB_H_
39 #define PCL_ROS_NORMAL_3D_TBB_H_
44 #include <pcl/features/normal_3d_tbb.h>
56 pcl::NormalEstimationTBB<pcl::PointXYZ, pcl::Normal>
impl_;
78 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84 #endif //#ifndef PCL_ROS_NORMAL_3D_TBB_H_
pcl::IndicesPtr IndicesPtr
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
NormalEstimationTBB estimates local surface properties at each 3D point, such as surface normals and ...
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).
pcl::PointCloud< pcl::Normal > PointCloudOut
ros::Publisher pub_output_
The output PointCloud publisher.
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
pcl::NormalEstimationTBB< pcl::PointXYZ, pcl::Normal > impl_
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40