Jafar
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
fileIO.hpp
00001 #ifndef VELODYNEUTILS_FILE_IO_HPP
00002 #define VELODYNEUTILS_FILE_IO_HPP
00003 
00004 #include <sys/time.h> // Necessary for velodyneLib.h
00005 #include <sys/types.h> // Necessary for velodyneLib.h and for libregionMap.h
00006 
00007 #include <string>
00008 
00009 #include <libregionMap.h>
00010 #include <velodyne/velodyneLib.h>
00011 
00012 #include <Eigen/Geometry>
00013 #include <pcl/io/pcd_io.h>
00014 #include <pcl/point_cloud.h>
00015 #include <pcl/point_types.h>
00016 
00017 #include "points.hpp"
00018 
00019 namespace jafar {
00020 namespace velodyneutils {
00021 
00025 class ReaderPosition {
00026 public:
00027     ReaderPosition();
00028     ReaderPosition(const std::string& fileNameIn);
00029     ReaderPosition(const std::string& baseFileNameIn, int fileNumIn);
00030     ~ReaderPosition();
00031 
00032     const std::string& getFileName() const;
00033     const std::string& getBaseFileName() const;
00034     int getFileNum() const;
00035     int setFileName(const std::string& fileName);
00036     int setBaseFileName(const std::string& baseFileName);
00037     int setFileNum(int fileNum);
00038     int load(Eigen::Affine3f& output);
00039 
00040 private:
00041     std::string fileName;
00042     std::string baseFileName;
00043     int fileNum;
00044 
00045     void composeFileName();
00046 };
00047 
00051 class ReaderVelodyneImage3D {
00052 public:
00053     ReaderVelodyneImage3D();
00054     ReaderVelodyneImage3D(const std::string& fileNameIn,
00055                           bool oldImage3DEnabledIn,
00056                           VELODYNE_MODEL modelIn);
00057     ReaderVelodyneImage3D(const std::string& baseFileNameIn, int fileNumIn,
00058                           bool oldImage3DEnabledIn, VELODYNE_MODEL modelIn);
00059     ~ReaderVelodyneImage3D();
00060 
00061     const std::string& getFileName() const;
00062     const std::string& getBaseFileName() const;
00063     int getFileNum() const;
00064     int setFileName(const std::string& fileName);
00065     int setBaseFileName(const std::string& baseFileName);
00066     int setFileNum(int fileNum);
00067     void enableOldImage3D(bool enable);
00068     int setVelodyneModel(VELODYNE_MODEL model);
00069     int load(pcl::PointCloud<pcl::PointXYZL>& output);
00070 
00071 private:
00072     std::string fileName;
00073     std::string baseFileName;
00074     int fileNum;
00075     bool oldImage3DEnabled;
00076     VELODYNE_MODEL model;
00077 
00078     void composeFileName();
00079 };
00080 
00084 class Reader3DImage {
00085 public:
00086     Reader3DImage();
00087     Reader3DImage(const std::string& fileNameIn);
00088     Reader3DImage(const std::string& baseFileNameIn, int fileNumIn);
00089     ~Reader3DImage();
00090 
00091     const std::string& getFileName() const;
00092     const std::string& getBaseFileName() const;
00093     int getFileNum() const;
00094     int setFileName(const std::string& fileName);
00095     int setBaseFileName(const std::string& baseFileName);
00096     int setFileNum(int fileNum);
00097 
00098     int load(pcl::PointCloud<PointXYZIL>& output);
00099 
00100 private:
00101     std::string fileName;
00102     std::string baseFileName;
00103     int fileNum;
00104 
00105     void composeFileName();
00106 };
00107 
00111 class ReaderRegionMap {
00112 public:
00113     ReaderRegionMap();
00114     ReaderRegionMap(const std::string& fileNameIn);
00115     ReaderRegionMap(const std::string& baseFileNameIn, int fileNumIn);
00116     ~ReaderRegionMap();
00117 
00118     const std::string& getFileName() const;
00119     const std::string& getBaseFileName() const;
00120     int getFileNum() const;
00121     int setFileName(const std::string& fileName);
00122     int setBaseFileName(const std::string& baseFileName);
00123     int setFileNum(int fileNum);
00124 
00125     int load(pcl::PointCloud<PointRegionMap>& output);
00126     int load(REGION_MAP& output);
00127 
00128 private:
00129     std::string fileName;
00130     std::string baseFileName;
00131     int fileNum;
00132 
00133     void composeFileName();
00134 };
00135 
00139 template<typename PointT>
00140 class WriterPCD : pcl::PCDWriter {
00141 public:
00142     typedef pcl::PCDWriter BaseClass;
00143     typedef pcl::PointCloud<PointT> PointCloud;
00144     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00145 
00146     WriterPCD();
00147     WriterPCD(bool binaryIn, const std::string& fileNameIn);
00148     WriterPCD(bool binaryIn, const std::string& baseFileNameIn, int fileNumIn);
00149     ~WriterPCD();
00150 
00151     const std::string& getFileName() const;
00152     const std::string& getBaseFileName() const;
00153     int getFileNum() const;
00154     void setInputCloud(const PointCloudConstPtr& input);
00155     int setBinary(bool binary);
00156     int setFileName(const std::string& fileName);
00157     int setBaseFileName(const std::string& baseFileName);
00158     int setFileNum(int fileNum);
00159     int write();
00160 
00161 private:
00162     PointCloudConstPtr input_;
00163     bool binary;
00164     std::string fileName;
00165     std::string baseFileName;
00166     int fileNum;
00167 
00168     void composeFileName();
00169 };
00170 
00171 } // namespace velodyneutils
00172 } // namespace jafar
00173 
00174 #endif // VELODYNEUTILS_FILE_IO_HPP
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines

Generated on Wed Oct 15 2014 00:37:29 for Jafar by doxygen 1.7.6.1
LAAS-CNRS