#include <feature.h>
Public Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef pcl::PointCloud < pcl::Normal > | PointCloudN |
typedef PointCloudN::ConstPtr | PointCloudNConstPtr |
typedef PointCloudN::Ptr | PointCloudNPtr |
Public Member Functions | |
FeatureFromNormals () | |
Protected Member Functions | |
virtual bool | childInit (ros::NodeHandle &nh)=0 |
Child initialization routine. Internal method. | |
virtual void | computePublish (const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0 |
Compute the feature and publish it. | |
virtual void | emptyPublish (const PointCloudInConstPtr &cloud)=0 |
Publish an empty point cloud of the feature output type. | |
Protected Attributes | |
PointCloudNConstPtr | normals_ |
A pointer to the input dataset that contains the point normals of the XYZ dataset. | |
Private Member Functions | |
void | computePublish (const PointCloudInConstPtr &, const PointCloudInConstPtr &, const IndicesPtr &) |
Internal method. | |
void | input_normals_surface_indices_callback (const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices) |
Input point cloud callback. Used when use_indices and use_surface are set. | |
virtual void | onInit () |
Nodelet initialization routine. | |
Private Attributes | |
message_filters::Subscriber < PointCloudN > | sub_normals_filter_ |
The normals PointCloud subscriber filter. | |
boost::shared_ptr < message_filters::Synchronizer < sync_policies::ApproximateTime < PointCloudIn, PointCloudN, PointCloudIn, PointIndices > > > | sync_input_normals_surface_indices_a_ |
Synchronized input, normals, surface, and point indices. | |
boost::shared_ptr < message_filters::Synchronizer < sync_policies::ExactTime < PointCloudIn, PointCloudN, PointCloudIn, PointIndices > > > | sync_input_normals_surface_indices_e_ |
typedef sensor_msgs::PointCloud2 pcl_ros::FeatureFromNormals::PointCloud2 |
Reimplemented from pcl_ros::PCLNodelet.
pcl_ros::FeatureFromNormals::FeatureFromNormals | ( | ) | [inline] |
virtual bool pcl_ros::FeatureFromNormals::childInit | ( | ros::NodeHandle & | nh | ) | [protected, pure virtual] |
Child initialization routine. Internal method.
Implements pcl_ros::Feature.
Implemented in pcl_ros::FPFHEstimation, pcl_ros::PFHEstimation, pcl_ros::FPFHEstimationOMP, pcl_ros::BoundaryEstimation, pcl_ros::PrincipalCurvaturesEstimation, and pcl_ros::VFHEstimation.
virtual void pcl_ros::FeatureFromNormals::computePublish | ( | const PointCloudInConstPtr & | cloud, |
const PointCloudNConstPtr & | normals, | ||
const PointCloudInConstPtr & | surface, | ||
const IndicesPtr & | indices | ||
) | [protected, pure virtual] |
Compute the feature and publish it.
Implemented in pcl_ros::FPFHEstimation, pcl_ros::PFHEstimation, pcl_ros::FPFHEstimationOMP, pcl_ros::BoundaryEstimation, pcl_ros::PrincipalCurvaturesEstimation, and pcl_ros::VFHEstimation.
void pcl_ros::FeatureFromNormals::computePublish | ( | const PointCloudInConstPtr & | , |
const PointCloudInConstPtr & | , | ||
const IndicesPtr & | |||
) | [inline, private, virtual] |
virtual void pcl_ros::FeatureFromNormals::emptyPublish | ( | const PointCloudInConstPtr & | cloud | ) | [protected, pure virtual] |
Publish an empty point cloud of the feature output type.
Implements pcl_ros::Feature.
Implemented in pcl_ros::FPFHEstimation, pcl_ros::PFHEstimation, pcl_ros::FPFHEstimationOMP, pcl_ros::BoundaryEstimation, pcl_ros::PrincipalCurvaturesEstimation, and pcl_ros::VFHEstimation.
void pcl_ros::FeatureFromNormals::input_normals_surface_indices_callback | ( | const PointCloudInConstPtr & | cloud, |
const PointCloudNConstPtr & | cloud_normals, | ||
const PointCloudInConstPtr & | cloud_surface, | ||
const PointIndicesConstPtr & | indices | ||
) | [private] |
Input point cloud callback. Used when use_indices and use_surface are set.
cloud | the pointer to the input point cloud |
cloud_normals | the pointer to the input point cloud normals |
cloud_surface | the pointer to the surface point cloud |
indices | the pointer to the input point cloud indices |
DEBUG
Definition at line 356 of file features/feature.cpp.
void pcl_ros::FeatureFromNormals::onInit | ( | ) | [private, virtual] |
Nodelet initialization routine.
Reimplemented from pcl_ros::Feature.
Definition at line 250 of file features/feature.cpp.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > pcl_ros::FeatureFromNormals::sync_input_normals_surface_indices_e_ [private] |