Classes | Public Member Functions | Private Member Functions | Private Attributes
pcl::PCDGrabberBase Class Reference

Base class for PCD file grabber. More...

#include <pcd_grabber.h>

Inheritance diagram for pcl::PCDGrabberBase:
Inheritance graph
[legend]

List of all members.

Classes

struct  PCDGrabberImpl

Public Member Functions

virtual float getFramesPerSecond () const
 Returns the frames_per_second. 0 if grabber is trigger-based.
virtual std::string getName () const
bool isRepeatOn () const
 Returns whether the repeat flag is on.
virtual bool isRunning () const
 whether the grabber is started (publishing) or not.
PCDGrabberBaseoperator= (const PCDGrabberBase &src)
 Copy operator.
 PCDGrabberBase (const std::string &pcd_file, float frames_per_second, bool repeat)
 Constructor taking just one PCD file or one TAR file containing multiple PCD files.
 PCDGrabberBase (const std::vector< std::string > &pcd_files, float frames_per_second, bool repeat)
 Constructor taking a list of paths to PCD files, that are played in the order they appear in the list.
 PCDGrabberBase (const PCDGrabberBase &src)
 Copy constructor.
virtual void rewind ()
 Rewinds to the first PCD file in the list.
virtual void start ()
 Starts playing the list of PCD files if frames_per_second is > 0. Otherwise it works as a trigger: publishes only the next PCD file in the list.
virtual void stop ()
 Stops playing the list of PCD files if frames_per_second is > 0. Otherwise the method has no effect.
virtual void trigger ()
 Triggers a callback with new data.
virtual ~PCDGrabberBase () throw ()
 Virtual destructor.

Private Member Functions

virtual void publish (const sensor_msgs::PointCloud2 &blob, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation) const =0

Private Attributes

PCDGrabberImplimpl_

Detailed Description

Base class for PCD file grabber.

Definition at line 58 of file pcd_grabber.h.


Constructor & Destructor Documentation

pcl::PCDGrabberBase::PCDGrabberBase ( const std::string &  pcd_file,
float  frames_per_second,
bool  repeat 
)

Constructor taking just one PCD file or one TAR file containing multiple PCD files.

Parameters:
[in]pcd_filepath to the PCD file
[in]frames_per_secondframes per second. If 0, start() functions like a trigger, publishing the next PCD in the list.
[in]repeatwhether to play PCD file in an endless loop or not.

Definition at line 269 of file pcd_grabber.cpp.

pcl::PCDGrabberBase::PCDGrabberBase ( const std::vector< std::string > &  pcd_files,
float  frames_per_second,
bool  repeat 
)

Constructor taking a list of paths to PCD files, that are played in the order they appear in the list.

Parameters:
[in]pcd_filesvector of paths to PCD files.
[in]frames_per_secondframes per second. If 0, start() functions like a trigger, publishing the next PCD in the list.
[in]repeatwhether to play PCD file in an endless loop or not.

Definition at line 275 of file pcd_grabber.cpp.

Copy constructor.

Parameters:
[in]srcthe PCD Grabber base object to copy into this

Definition at line 78 of file pcd_grabber.h.

pcl::PCDGrabberBase::~PCDGrabberBase ( ) throw () [virtual]

Virtual destructor.

Definition at line 281 of file pcd_grabber.cpp.


Member Function Documentation

float pcl::PCDGrabberBase::getFramesPerSecond ( ) const [virtual]

Returns the frames_per_second. 0 if grabber is trigger-based.

Implements pcl::Grabber.

Definition at line 343 of file pcd_grabber.cpp.

std::string pcl::PCDGrabberBase::getName ( ) const [virtual]
Returns:
The name of the grabber

Implements pcl::Grabber.

Definition at line 329 of file pcd_grabber.cpp.

Returns whether the repeat flag is on.

Definition at line 350 of file pcd_grabber.cpp.

bool pcl::PCDGrabberBase::isRunning ( ) const [virtual]

whether the grabber is started (publishing) or not.

Returns:
true only if publishing.

Implements pcl::Grabber.

Definition at line 322 of file pcd_grabber.cpp.

PCDGrabberBase& pcl::PCDGrabberBase::operator= ( const PCDGrabberBase src) [inline]

Copy operator.

Parameters:
[in]srcthe PCD Grabber base object to copy into this

Definition at line 87 of file pcd_grabber.h.

virtual void pcl::PCDGrabberBase::publish ( const sensor_msgs::PointCloud2 &  blob,
const Eigen::Vector4f &  origin,
const Eigen::Quaternionf &  orientation 
) const [private, pure virtual]

Implemented in pcl::PCDGrabber< PointT >.

void pcl::PCDGrabberBase::rewind ( ) [virtual]

Rewinds to the first PCD file in the list.

Definition at line 336 of file pcd_grabber.cpp.

void pcl::PCDGrabberBase::start ( ) [virtual]

Starts playing the list of PCD files if frames_per_second is > 0. Otherwise it works as a trigger: publishes only the next PCD file in the list.

Implements pcl::Grabber.

Definition at line 289 of file pcd_grabber.cpp.

void pcl::PCDGrabberBase::stop ( ) [virtual]

Stops playing the list of PCD files if frames_per_second is > 0. Otherwise the method has no effect.

Implements pcl::Grabber.

Definition at line 302 of file pcd_grabber.cpp.

void pcl::PCDGrabberBase::trigger ( ) [virtual]

Triggers a callback with new data.

Definition at line 313 of file pcd_grabber.cpp.


Member Data Documentation

Definition at line 135 of file pcd_grabber.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