pcl::PCLBase< sensor_msgs::PointCloud2 > Class Template Reference

#include <pcl_base.h>

Inheritance diagram for pcl::PCLBase< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef sensor_msgs::PointCloud2 PointCloud2
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
typedef PointCloud2::Ptr PointCloud2Ptr
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr

Public Member Functions

IndicesConstPtr const getIndices ()
 Get a pointer to the vector of indices used.
PointCloud2ConstPtr const getInputCloud ()
 Get a pointer to the input point cloud dataset.
 PCLBase ()
 Empty constructor.
void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
void setInputCloud (const PointCloud2ConstPtr &cloud)
 Provide a pointer to the input dataset.

Protected Member Functions

bool deinitCompute ()
 This method should get called after finishing the actual computation.
bool initCompute ()
 This method should get called before starting the actual computation.

Protected Attributes

bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.
std::vector< int > field_sizes_
 The size of each individual field.
IndicesConstPtr indices_
 A pointer to the vector of point indices to use.
PointCloud2ConstPtr input_
 The input point cloud dataset.
bool use_indices_
 Set to true if point indices are used.
std::string x_field_name_
 The desired x-y-z field names.
int x_idx_
 The x-y-z fields indices.
std::string y_field_name_
int y_idx_
std::string z_field_name_
int z_idx_

Detailed Description

template<>
class pcl::PCLBase< sensor_msgs::PointCloud2 >

Definition at line 174 of file pcl_base.h.


Member Typedef Documentation

typedef PointCloud2::ConstPtr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr

Definition at line 182 of file pcl_base.h.

Definition at line 181 of file pcl_base.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 185 of file pcl_base.h.


Member Function Documentation

bool pcl::PCLBase< sensor_msgs::PointCloud2 >::deinitCompute (  )  [protected]

This method should get called after finishing the actual computation.

Definition at line 68 of file pcl_base.cpp.

IndicesConstPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getIndices (  )  [inline]

Get a pointer to the vector of indices used.

Definition at line 223 of file pcl_base.h.

PointCloud2ConstPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getInputCloud (  )  [inline]

Get a pointer to the input point cloud dataset.

Definition at line 197 of file pcl_base.h.

bool pcl::PCLBase< sensor_msgs::PointCloud2 >::initCompute (  )  [protected]

This method should get called before starting the actual computation.

Definition at line 82 of file pcl_base.cpp.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices ( const PointIndicesConstPtr indices  )  [inline]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
indices a pointer to the vector of indices that represents the input data.

Definition at line 214 of file pcl_base.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices ( const IndicesConstPtr indices  )  [inline]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
indices a pointer to the vector of indices that represents the input data.

Definition at line 203 of file pcl_base.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setInputCloud ( const PointCloud2ConstPtr cloud  ) 

Provide a pointer to the input dataset.

Parameters:
cloud the const boost shared pointer to a PointCloud message
Author:
Radu Bogdan Rusu
Parameters:
cloud the const boost shared pointer to a PointCloud message

Definition at line 52 of file pcl_base.cpp.


Member Data Documentation

If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.

Definition at line 236 of file pcl_base.h.

std::vector<int> pcl::PCLBase< sensor_msgs::PointCloud2 >::field_sizes_ [protected]

The size of each individual field.

Definition at line 239 of file pcl_base.h.

A pointer to the vector of point indices to use.

Definition at line 230 of file pcl_base.h.

The input point cloud dataset.

Definition at line 227 of file pcl_base.h.

Set to true if point indices are used.

Definition at line 233 of file pcl_base.h.

The desired x-y-z field names.

Definition at line 245 of file pcl_base.h.

The x-y-z fields indices.

Definition at line 242 of file pcl_base.h.

Definition at line 245 of file pcl_base.h.

Definition at line 242 of file pcl_base.h.

Definition at line 245 of file pcl_base.h.

Definition at line 242 of file pcl_base.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:20 2013