#include <pcd_grabber.h>

Public Member Functions | |
| PCDGrabber (const std::string &pcd_path, float frames_per_second=0, bool repeat=false) | |
| PCDGrabber (const std::vector< std::string > &pcd_files, float frames_per_second=0, bool repeat=false) | |
Protected Member Functions | |
| virtual void | publish (const sensor_msgs::PointCloud2 &blob, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation) const |
Protected Attributes | |
| boost::signals2::signal< void(const boost::shared_ptr< const pcl::PointCloud< PointT > > &)> * | signal_ |
Definition at line 141 of file pcd_grabber.h.
| pcl::PCDGrabber< PointT >::PCDGrabber | ( | const std::string & | pcd_path, |
| float | frames_per_second = 0, |
||
| bool | repeat = false |
||
| ) |
Definition at line 159 of file pcd_grabber.h.
| pcl::PCDGrabber< PointT >::PCDGrabber | ( | const std::vector< std::string > & | pcd_files, |
| float | frames_per_second = 0, |
||
| bool | repeat = false |
||
| ) |
Definition at line 170 of file pcd_grabber.h.
| void pcl::PCDGrabber< PointT >::publish | ( | const sensor_msgs::PointCloud2 & | blob, |
| const Eigen::Vector4f & | origin, | ||
| const Eigen::Quaternionf & | orientation | ||
| ) | const [protected, virtual] |
Implements pcl::PCDGrabberBase.
Definition at line 181 of file pcd_grabber.h.
boost::signals2::signal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>* pcl::PCDGrabber< PointT >::signal_ [protected] |
Definition at line 150 of file pcd_grabber.h.