Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
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

IndicesPtr 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 IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
void setIndices (const PointIndicesConstPtr &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.
virtual ~PCLBase ()
 destructor.

Protected Member Functions

bool deinitCompute ()
bool initCompute ()

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.
IndicesPtr 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 272 of file pcl_base.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl::PCLBase< sensor_msgs::PointCloud2 >::PointCloud2
typedef PointCloud2::ConstPtr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr
typedef PointCloud2::Ptr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointCloud2Ptr
typedef PointIndices::ConstPtr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointIndicesConstPtr

Definition at line 280 of file pcl_base.h.

typedef PointIndices::Ptr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointIndicesPtr

Definition at line 279 of file pcl_base.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 283 of file pcl_base.h.

virtual pcl::PCLBase< sensor_msgs::PointCloud2 >::~PCLBase ( ) [inline, virtual]

destructor.

Definition at line 289 of file pcl_base.h.


Member Function Documentation

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

Definition at line 106 of file pcl_base.cpp.

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

Get a pointer to the vector of indices used.

Definition at line 329 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 303 of file pcl_base.h.

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

Definition at line 113 of file pcl_base.cpp.

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

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

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

Definition at line 309 of file pcl_base.h.

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:
indicesa pointer to the vector of indices that represents the input data.

Definition at line 320 of file pcl_base.h.

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

Provide a pointer to the input dataset.

Parameters:
cloudthe const boost shared pointer to a PointCloud message

Definition at line 44 of file pcl_base.cpp.


Member Data Documentation

bool pcl::PCLBase< sensor_msgs::PointCloud2 >::fake_indices_ [protected]

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

Definition at line 342 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 345 of file pcl_base.h.

IndicesPtr pcl::PCLBase< sensor_msgs::PointCloud2 >::indices_ [protected]

A pointer to the vector of point indices to use.

Definition at line 336 of file pcl_base.h.

PointCloud2ConstPtr pcl::PCLBase< sensor_msgs::PointCloud2 >::input_ [protected]

The input point cloud dataset.

Definition at line 333 of file pcl_base.h.

bool pcl::PCLBase< sensor_msgs::PointCloud2 >::use_indices_ [protected]

Set to true if point indices are used.

Definition at line 339 of file pcl_base.h.

std::string pcl::PCLBase< sensor_msgs::PointCloud2 >::x_field_name_ [protected]

The desired x-y-z field names.

Definition at line 351 of file pcl_base.h.

int pcl::PCLBase< sensor_msgs::PointCloud2 >::x_idx_ [protected]

The x-y-z fields indices.

Definition at line 348 of file pcl_base.h.

std::string pcl::PCLBase< sensor_msgs::PointCloud2 >::y_field_name_ [protected]

Definition at line 351 of file pcl_base.h.

int pcl::PCLBase< sensor_msgs::PointCloud2 >::y_idx_ [protected]

Definition at line 348 of file pcl_base.h.

std::string pcl::PCLBase< sensor_msgs::PointCloud2 >::z_field_name_ [protected]

Definition at line 351 of file pcl_base.h.

int pcl::PCLBase< sensor_msgs::PointCloud2 >::z_idx_ [protected]

Definition at line 348 of file pcl_base.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:48