Class FeatureFromNormals
Defined in File feature.hpp
Inheritance Relationships
Base Type
public pcl_ros::Feature
(Class Feature)
Derived Types
public pcl_ros::BoundaryEstimation
(Class BoundaryEstimation)public pcl_ros::FPFHEstimation
(Class FPFHEstimation)public pcl_ros::FPFHEstimationOMP
(Class FPFHEstimationOMP)public pcl_ros::PFHEstimation
(Class PFHEstimation)public pcl_ros::PrincipalCurvaturesEstimation
(Class PrincipalCurvaturesEstimation)public pcl_ros::SHOTEstimation
(Class SHOTEstimation)public pcl_ros::SHOTEstimationOMP
(Class SHOTEstimationOMP)public pcl_ros::VFHEstimation
(Class VFHEstimation)
Class Documentation
-
class FeatureFromNormals : public pcl_ros::Feature
Subclassed by pcl_ros::BoundaryEstimation, pcl_ros::FPFHEstimation, pcl_ros::FPFHEstimationOMP, pcl_ros::PFHEstimation, pcl_ros::PrincipalCurvaturesEstimation, pcl_ros::SHOTEstimation, pcl_ros::SHOTEstimationOMP, pcl_ros::VFHEstimation
Public Types
-
typedef sensor_msgs::PointCloud2 PointCloud2
-
typedef pcl::PointCloud<pcl::Normal> PointCloudN
-
typedef boost::shared_ptr<PointCloudN> PointCloudNPtr
-
typedef boost::shared_ptr<const PointCloudN> PointCloudNConstPtr
Public Functions
-
inline FeatureFromNormals()
Protected Functions
-
virtual bool childInit(ros::NodeHandle &nh) = 0
Child initialization routine. Internal method.
-
virtual void emptyPublish(const PointCloudInConstPtr &cloud) = 0
Publish an empty point cloud of the feature output type.
-
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices) = 0
Compute the feature and publish it.
Protected Attributes
-
PointCloudNConstPtr normals_
A pointer to the input dataset that contains the point normals of the XYZ dataset.
-
typedef sensor_msgs::PointCloud2 PointCloud2