00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2012-, Open Perception, Inc. 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of the copyright holder(s) nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 */ 00037 00038 #ifndef PCL_IO_ASCII_IO_H_ 00039 #define PCL_IO_ASCII_IO_H_ 00040 00041 #include <pcl/io/file_io.h> 00042 #include <pcl/PCLPointField.h> 00043 #include <pcl/common/io.h> 00044 00045 00046 namespace pcl 00047 { 00054 class PCL_EXPORTS ASCIIReader : public FileReader 00055 { 00056 public: 00057 ASCIIReader (); 00058 virtual ~ASCIIReader (); 00059 using FileReader::read; 00060 00061 /* Load only the meta information (number of points, their types, etc), 00062 * and not the points themselves, from a given FILE file. Useful for fast 00063 * evaluation of the underlying data structure. 00064 * 00065 * Returns: 00066 * * < 0 (-1) on error 00067 * * > 0 on success 00068 * \param[in] file_name the name of the file to load 00069 * \param[out] cloud the resultant point cloud dataset (only the header will be filled) 00070 * \param[out] origin the sensor acquisition origin (only for > FILE_V7 - null if not present) 00071 * \param[out] orientation the sensor acquisition orientation (only for > FILE_V7 - identity if not present) 00072 * \param[out] file_version the FILE version of the file (either FILE_V6 or FILE_V7) 00073 * \param[out] data_type the type of data (binary data=1, ascii=0, etc) 00074 * \param[out] data_idx the offset of cloud data within the file 00075 * \param[in] offset the offset in the file where to expect the true header to begin. 00076 * One usage example for setting the offset parameter is for reading 00077 * data from a TAR "archive containing multiple files: TAR files always 00078 * add a 512 byte header in front of the actual file, so set the offset 00079 * to the next byte after the header (e.g., 513). 00080 */ 00081 virtual int 00082 readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, 00083 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, 00084 int &file_version, int &data_type, unsigned int &data_idx, const int offset = 0) ; 00085 00086 00099 virtual int 00100 read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, 00101 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, 00102 const int offset = 0); 00103 00107 void 00108 setInputFields (const std::vector<pcl::PCLPointField>& fields); 00109 00110 00114 template<typename PointT> 00115 void setInputFields (const PointT p = PointT ()); 00116 00117 00123 void 00124 setSepChars (const std::string &chars); 00125 00129 void 00130 setExtension (const std::string &ext) { extension_ = ext; } 00131 00132 protected: 00133 std::string sep_chars_; 00134 std::string extension_; 00135 std::vector<pcl::PCLPointField> fields_; 00136 std::string name_; 00137 00138 00145 int 00146 parse (const std::string& token, const pcl::PCLPointField& field, uint8_t* data_target); 00147 00152 uint32_t 00153 typeSize (int type); 00154 }; 00155 } 00156 00158 template<typename PointT> void 00159 pcl::ASCIIReader::setInputFields (const PointT p) 00160 { 00161 (void) p; 00162 00163 pcl::getFields<PointT> (fields_); 00164 00165 // Remove empty fields and adjust offset 00166 int offset =0; 00167 for (std::vector<pcl::PCLPointField>::iterator field_iter = fields_.begin (); 00168 field_iter != fields_.end (); field_iter++) 00169 { 00170 if (field_iter->name == "_") 00171 field_iter = fields_.erase (field_iter); 00172 field_iter->offset = offset; 00173 offset += typeSize (field_iter->datatype); 00174 } 00175 } 00176 00177 #endif // PCL_IO_ASCII_IO_H_