Classes | Namespaces | Functions
file_io.h File Reference
#include <pcl/pcl_macros.h>
#include <pcl/common/io.h>
#include <boost/numeric/conversion/cast.hpp>
#include <cmath>
#include <sstream>
Include dependency graph for io/include/pcl/io/file_io.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  pcl::FileReader
 Point Cloud Data (FILE) file format reader interface. Any (FILE) format file reader should implement its virtual methodes. More...
class  pcl::FileWriter
 Point Cloud Data (FILE) file format writer. Any (FILE) format file reader should implement its virtual methodes. More...

Namespaces

namespace  pcl

Functions

template<typename Type >
void pcl::copyStringValue (const std::string &st, sensor_msgs::PointCloud2 &cloud, unsigned int point_index, unsigned int field_idx, unsigned int fields_count)
 Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string.
template<>
void pcl::copyStringValue< int8_t > (const std::string &st, sensor_msgs::PointCloud2 &cloud, unsigned int point_index, unsigned int field_idx, unsigned int fields_count)
template<>
void pcl::copyStringValue< uint8_t > (const std::string &st, sensor_msgs::PointCloud2 &cloud, unsigned int point_index, unsigned int field_idx, unsigned int fields_count)
template<typename Type >
void pcl::copyValueString (const sensor_msgs::PointCloud2 &cloud, const unsigned int point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream)
 insers a value of type Type (uchar, char, uint, int, float, double, ...) into a stringstream.
template<>
void pcl::copyValueString< int8_t > (const sensor_msgs::PointCloud2 &cloud, const unsigned int point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream)
template<>
void pcl::copyValueString< uint8_t > (const sensor_msgs::PointCloud2 &cloud, const unsigned int point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream)
template<typename Type >
bool pcl::isValueFinite (const sensor_msgs::PointCloud2 &cloud, const unsigned int point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count)
 Check whether a given value of type Type (uchar, char, uint, int, float, double, ...) is finite or not.


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