Public Member Functions | Public Attributes
pcl::ImageGrabberBase::ImageGrabberImpl Struct Reference

List of all members.

Public Member Functions

bool getCloudAt (size_t idx, pcl::PCLPointCloud2 &blob, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, double &fx, double &fy, double &cx, double &cy) const
 Get cloud at a particular location.
bool getCloudPCLZF (size_t idx, pcl::PCLPointCloud2 &blob, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, double &fx, double &fy, double &cx, double &cy) const
 Get cloud at a particular location.
bool getCloudVTK (size_t idx, pcl::PCLPointCloud2 &blob, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation) const
 Get cloud at a particular location.
bool getTimestampFromFilepath (const std::string &filepath, uint64_t &timestamp) const
 ImageGrabberImpl (pcl::ImageGrabberBase &grabber, const std::string &dir, float frames_per_second, bool repeat, bool pclzf_mode=false)
 Implementation of ImageGrabber.
 ImageGrabberImpl (pcl::ImageGrabberBase &grabber, const std::string &rgb_dir, const std::string &depth_dir, float frames_per_second, bool repeat)
 For now, split rgb / depth folders only makes sense for VTK images.
 ImageGrabberImpl (pcl::ImageGrabberBase &grabber, const std::vector< std::string > &depth_image_files, float frames_per_second, bool repeat)
bool isValidExtension (const std::string &extension)
 True if it is an image we know how to read.
void loadDepthAndRGBFiles (const std::string &dir)
void loadDepthAndRGBFiles (const std::string &depth_dir, const std::string &rgb_dir)
void loadNextCloud ()
 Read ahead -- figure out whether we are in VTK image or PCLZF mode.
void loadPCLZFFiles (const std::string &dir)
 Scrapes a directory for pclzf files which contain "rgb" or "depth and updates.
size_t numFrames () const
void rewindOnce ()
 Convenience function to rewind to the last frame.
void trigger ()

Public Attributes

size_t cur_frame_
std::vector< std::stringdepth_image_files_
float depth_image_units_
std::vector< std::stringdepth_pclzf_files_
double focal_length_x_
double focal_length_y_
float frames_per_second_
pcl::ImageGrabberBasegrabber_
bool manual_intrinsics_
pcl::PCLPointCloud2 next_cloud_
pcl::PointCloud
< pcl::PointXYZRGBA
next_cloud_color_
pcl::PointCloud< pcl::PointXYZnext_cloud_depth_
 Two cases, for depth only and depth+color.
unsigned int num_threads_
Eigen::Quaternionf orientation_
Eigen::Vector4f origin_
bool pclzf_mode_
 Flag to say if a user set the focal length by hand.
double principal_point_x_
double principal_point_y_
bool repeat_
std::vector< std::stringrgb_image_files_
std::vector< std::stringrgb_pclzf_files_
bool running_
TimeTrigger time_trigger_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool 
valid_
std::vector< std::stringxml_files_

Detailed Description

Definition at line 60 of file image_grabber.cpp.


Constructor & Destructor Documentation

pcl::ImageGrabberBase::ImageGrabberImpl::ImageGrabberImpl ( pcl::ImageGrabberBase grabber,
const std::string dir,
float  frames_per_second,
bool  repeat,
bool  pclzf_mode = false 
)

Implementation of ImageGrabber.

Definition at line 174 of file image_grabber.cpp.

pcl::ImageGrabberBase::ImageGrabberImpl::ImageGrabberImpl ( pcl::ImageGrabberBase grabber,
const std::string rgb_dir,
const std::string depth_dir,
float  frames_per_second,
bool  repeat 
)

For now, split rgb / depth folders only makes sense for VTK images.

Definition at line 211 of file image_grabber.cpp.

pcl::ImageGrabberBase::ImageGrabberImpl::ImageGrabberImpl ( pcl::ImageGrabberBase grabber,
const std::vector< std::string > &  depth_image_files,
float  frames_per_second,
bool  repeat 
)

Definition at line 241 of file image_grabber.cpp.


Member Function Documentation

bool pcl::ImageGrabberBase::ImageGrabberImpl::getCloudAt ( size_t  idx,
pcl::PCLPointCloud2 blob,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation,
double &  fx,
double &  fy,
double &  cx,
double &  cy 
) const

Get cloud at a particular location.

Definition at line 519 of file image_grabber.cpp.

bool pcl::ImageGrabberBase::ImageGrabberImpl::getCloudPCLZF ( size_t  idx,
pcl::PCLPointCloud2 blob,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation,
double &  fx,
double &  fy,
double &  cx,
double &  cy 
) const

Get cloud at a particular location.

Definition at line 681 of file image_grabber.cpp.

bool pcl::ImageGrabberBase::ImageGrabberImpl::getCloudVTK ( size_t  idx,
pcl::PCLPointCloud2 blob,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation 
) const

Get cloud at a particular location.

Definition at line 546 of file image_grabber.cpp.

bool pcl::ImageGrabberBase::ImageGrabberImpl::getTimestampFromFilepath ( const std::string filepath,
uint64_t &  timestamp 
) const

Checks if a timestamp is given in the filename And returns if so

Definition at line 496 of file image_grabber.cpp.

True if it is an image we know how to read.

Definition at line 471 of file image_grabber.cpp.

Scrapes a directory for image files which contain "rgb" or "depth" and updates our list accordingly

Definition at line 302 of file image_grabber.cpp.

Scrapes a directory for image files which contain "rgb" or "depth" and updates our list accordingly

Definition at line 344 of file image_grabber.cpp.

Read ahead -- figure out whether we are in VTK image or PCLZF mode.

Definition at line 271 of file image_grabber.cpp.

Scrapes a directory for pclzf files which contain "rgb" or "depth and updates.

Definition at line 419 of file image_grabber.cpp.

Definition at line 867 of file image_grabber.cpp.

Convenience function to rewind to the last frame.

Definition at line 488 of file image_grabber.cpp.

Definition at line 290 of file image_grabber.cpp.


Member Data Documentation

Definition at line 146 of file image_grabber.cpp.

Definition at line 139 of file image_grabber.cpp.

Definition at line 162 of file image_grabber.cpp.

Definition at line 142 of file image_grabber.cpp.

Definition at line 165 of file image_grabber.cpp.

Definition at line 166 of file image_grabber.cpp.

Definition at line 135 of file image_grabber.cpp.

Definition at line 134 of file image_grabber.cpp.

Definition at line 164 of file image_grabber.cpp.

Definition at line 150 of file image_grabber.cpp.

Definition at line 153 of file image_grabber.cpp.

Two cases, for depth only and depth+color.

Definition at line 152 of file image_grabber.cpp.

Definition at line 170 of file image_grabber.cpp.

Definition at line 155 of file image_grabber.cpp.

Definition at line 154 of file image_grabber.cpp.

Flag to say if a user set the focal length by hand.

Definition at line 160 of file image_grabber.cpp.

Definition at line 167 of file image_grabber.cpp.

Definition at line 168 of file image_grabber.cpp.

Definition at line 136 of file image_grabber.cpp.

Definition at line 140 of file image_grabber.cpp.

Definition at line 143 of file image_grabber.cpp.

Definition at line 137 of file image_grabber.cpp.

Definition at line 148 of file image_grabber.cpp.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool pcl::ImageGrabberBase::ImageGrabberImpl::valid_

Definition at line 157 of file image_grabber.cpp.

Definition at line 144 of file image_grabber.cpp.


The documentation for this struct was generated from the following file:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:53