Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
pcl_ros::FeatureFromNormals Class Reference

#include <feature.h>

Inheritance diagram for pcl_ros::FeatureFromNormals:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

Definition at line 184 of file feature.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl_ros::FeatureFromNormals::PointCloud2

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 187 of file feature.h.

Definition at line 189 of file feature.h.

typedef PointCloudN::ConstPtr pcl_ros::FeatureFromNormals::PointCloudNConstPtr

Definition at line 191 of file feature.h.

Definition at line 190 of file feature.h.


Constructor & Destructor Documentation

Definition at line 193 of file feature.h.


Member Function Documentation

virtual bool pcl_ros::FeatureFromNormals::childInit ( ros::NodeHandle nh) [protected, pure virtual]
virtual void pcl_ros::FeatureFromNormals::computePublish ( const PointCloudInConstPtr cloud,
const PointCloudNConstPtr normals,
const PointCloudInConstPtr surface,
const IndicesPtr indices 
) [protected, pure virtual]
void pcl_ros::FeatureFromNormals::computePublish ( const PointCloudInConstPtr ,
const PointCloudInConstPtr ,
const IndicesPtr  
) [inline, private, virtual]

Internal method.

Implements pcl_ros::Feature.

Definition at line 220 of file feature.h.

virtual void pcl_ros::FeatureFromNormals::emptyPublish ( const PointCloudInConstPtr cloud) [protected, pure virtual]
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.

Parameters:
cloudthe pointer to the input point cloud
cloud_normalsthe pointer to the input point cloud normals
cloud_surfacethe pointer to the surface point cloud
indicesthe 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.


Member Data Documentation

A pointer to the input dataset that contains the point normals of the XYZ dataset.

Definition at line 193 of file feature.h.

The normals PointCloud subscriber filter.

Definition at line 213 of file feature.h.

Synchronized input, normals, surface, and point indices.

Definition at line 216 of file feature.h.

Definition at line 217 of file feature.h.


The documentation for this class was generated from the following files:


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Jun 6 2019 21:01:44