pcd_io.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, 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 Willow Garage, Inc. 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  * $Id$
00037  *
00038  */
00039 
00040 #include <fstream>
00041 #include <fcntl.h>
00042 #include <string>
00043 #include <stdlib.h>
00044 #include <pcl/io/boost.h>
00045 #include <pcl/common/io.h>
00046 #include <pcl/io/pcd_io.h>
00047 #include <pcl/io/lzf.h>
00048 #include <pcl/console/time.h>
00049 
00050 #include <cstring>
00051 #include <cerrno>
00052 
00053 #ifdef _WIN32
00054 # include <io.h>
00055 # include <windows.h>
00056 # define pcl_open                    _open
00057 # define pcl_close(fd)               _close(fd)
00058 # define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin)
00059 #else
00060 # include <sys/mman.h>
00061 # define pcl_open                    open
00062 # define pcl_close(fd)               close(fd)
00063 # define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin)
00064 #endif
00065 #include <boost/version.hpp>
00066 
00068 void
00069 pcl::PCDWriter::setLockingPermissions (const std::string &file_name,
00070                                        boost::interprocess::file_lock &lock)
00071 {
00072   (void)file_name;
00073   (void)lock;
00074 #ifndef WIN32
00075   // Boost version 1.49 introduced permissions
00076 #if BOOST_VERSION >= 104900
00077   // Attempt to lock the file. 
00078   // For mandatory locking, the filesystem must be mounted with the "mand" option in Linux (see http://www.hackinglinuxexposed.com/articles/20030623.html)
00079   lock = boost::interprocess::file_lock (file_name.c_str ());
00080   if (lock.try_lock ())
00081     PCL_DEBUG ("[pcl::PCDWriter::setLockingPermissions] File %s locked succesfully.\n", file_name.c_str ());
00082   else
00083     PCL_DEBUG ("[pcl::PCDWriter::setLockingPermissions] File %s could not be locked!\n", file_name.c_str ());
00084 
00085   namespace fs = boost::filesystem;
00086   fs::permissions (fs::path (file_name), fs::add_perms | fs::set_gid_on_exe);
00087 #endif
00088 #endif
00089 }
00090 
00092 void
00093 pcl::PCDWriter::resetLockingPermissions (const std::string &file_name,
00094                                          boost::interprocess::file_lock &lock)
00095 {
00096   (void)file_name;
00097   (void)lock;
00098 #ifndef WIN32
00099   // Boost version 1.49 introduced permissions
00100 #if BOOST_VERSION >= 104900
00101   (void)file_name;
00102   namespace fs = boost::filesystem;
00103   fs::permissions (fs::path (file_name), fs::remove_perms | fs::set_gid_on_exe);
00104   lock.unlock ();
00105 #endif
00106 #endif
00107 }
00108 
00110 int
00111 pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00112                             Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, 
00113                             int &pcd_version, int &data_type, unsigned int &data_idx, const int offset)
00114 {
00115   // Default values
00116   data_idx = 0;
00117   data_type = 0;
00118   pcd_version = PCD_V6;
00119   origin      = Eigen::Vector4f::Zero ();
00120   orientation = Eigen::Quaternionf::Identity ();
00121   cloud.width = cloud.height = cloud.point_step = cloud.row_step = 0;
00122   cloud.data.clear ();
00123 
00124   // By default, assume that there are _no_ invalid (e.g., NaN) points
00125   //cloud.is_dense = true;
00126 
00127   int nr_points = 0;
00128   std::ifstream fs;
00129   std::string line;
00130 
00131   int specified_channel_count = 0;
00132 
00133   if (file_name == "" || !boost::filesystem::exists (file_name))
00134   {
00135     PCL_ERROR ("[pcl::PCDReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
00136     return (-1);
00137   }
00138 
00139   // Open file in binary mode to avoid problem of 
00140   // std::getline() corrupting the result of ifstream::tellg()
00141   fs.open (file_name.c_str (), std::ios::binary);
00142   if (!fs.is_open () || fs.fail ())
00143   {
00144     PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror(errno)); 
00145     fs.close ();
00146     return (-1);
00147   }
00148 
00149   // Seek at the given offset
00150   fs.seekg (offset, std::ios::beg);
00151 
00152   // field_sizes represents the size of one element in a field (e.g., float = 4, char = 1)
00153   // field_counts represents the number of elements in a field (e.g., x = 1, normal_x = 1, fpfh = 33)
00154   std::vector<int> field_sizes, field_counts;
00155   // field_types represents the type of data in a field (e.g., F = float, U = unsigned)
00156   std::vector<char> field_types;
00157   std::vector<std::string> st;
00158 
00159   // Read the header and fill it in with wonderful values
00160   try
00161   {
00162     while (!fs.eof ())
00163     {
00164       getline (fs, line);
00165       // Ignore empty lines
00166       if (line == "")
00167         continue;
00168 
00169       // Tokenize the line
00170       boost::trim (line);
00171       boost::split (st, line, boost::is_any_of ("\t\r "), boost::token_compress_on);
00172 
00173       std::stringstream sstream (line);
00174       sstream.imbue (std::locale::classic ());
00175 
00176       std::string line_type;
00177       sstream >> line_type;
00178 
00179       // Ignore comments
00180       if (line_type.substr (0, 1) == "#")
00181         continue;
00182 
00183       // Version numbers are not needed for now, but we are checking to see if they're there
00184       if (line_type.substr (0, 7) == "VERSION")
00185         continue;
00186 
00187       // Get the field indices (check for COLUMNS too for backwards compatibility)
00188       if ( (line_type.substr (0, 6) == "FIELDS") || (line_type.substr (0, 7) == "COLUMNS") )
00189       {
00190         specified_channel_count = static_cast<int> (st.size () - 1);
00191 
00192         // Allocate enough memory to accommodate all fields
00193         cloud.fields.resize (specified_channel_count);
00194         for (int i = 0; i < specified_channel_count; ++i)
00195         {
00196           std::string col_type = st.at (i + 1);
00197           cloud.fields[i].name = col_type;
00198         }
00199 
00200         // Default the sizes and the types of each field to float32 to avoid crashes while using older PCD files
00201         int offset = 0;
00202         for (int i = 0; i < specified_channel_count; ++i, offset += 4)
00203         {
00204           cloud.fields[i].offset   = offset;
00205           cloud.fields[i].datatype = pcl::PCLPointField::FLOAT32;
00206           cloud.fields[i].count    = 1;
00207         }
00208         cloud.point_step = offset;
00209         continue;
00210       }
00211 
00212       // Get the field sizes
00213       if (line_type.substr (0, 4) == "SIZE")
00214       {
00215         specified_channel_count = static_cast<int> (st.size () - 1);
00216 
00217         // Allocate enough memory to accommodate all fields
00218         if (specified_channel_count != static_cast<int> (cloud.fields.size ()))
00219           throw "The number of elements in <SIZE> differs than the number of elements in <FIELDS>!";
00220 
00221         // Resize to accommodate the number of values
00222         field_sizes.resize (specified_channel_count);
00223 
00224         int offset = 0;
00225         for (int i = 0; i < specified_channel_count; ++i)
00226         {
00227           int col_type ;
00228           sstream >> col_type;
00229           cloud.fields[i].offset = offset;                // estimate and save the data offsets
00230           offset += col_type;
00231           field_sizes[i] = col_type;                      // save a temporary copy
00232         }
00233         cloud.point_step = offset;
00234         //if (cloud.width != 0)
00235           //cloud.row_step   = cloud.point_step * cloud.width;
00236         continue;
00237       }
00238 
00239       // Get the field types
00240       if (line_type.substr (0, 4) == "TYPE")
00241       {
00242         if (field_sizes.empty ())
00243           throw "TYPE of FIELDS specified before SIZE in header!";
00244 
00245         specified_channel_count = static_cast<int> (st.size () - 1);
00246 
00247         // Allocate enough memory to accommodate all fields
00248         if (specified_channel_count != static_cast<int> (cloud.fields.size ()))
00249           throw "The number of elements in <TYPE> differs than the number of elements in <FIELDS>!";
00250 
00251         // Resize to accommodate the number of values
00252         field_types.resize (specified_channel_count);
00253 
00254         for (int i = 0; i < specified_channel_count; ++i)
00255         {
00256           field_types[i] = st.at (i + 1).c_str ()[0];
00257           cloud.fields[i].datatype = static_cast<uint8_t> (getFieldType (field_sizes[i], field_types[i]));
00258         }
00259         continue;
00260       }
00261 
00262       // Get the field counts
00263       if (line_type.substr (0, 5) == "COUNT")
00264       {
00265         if (field_sizes.empty () || field_types.empty ())
00266           throw "COUNT of FIELDS specified before SIZE or TYPE in header!";
00267 
00268         specified_channel_count = static_cast<int> (st.size () - 1);
00269 
00270         // Allocate enough memory to accommodate all fields
00271         if (specified_channel_count != static_cast<int> (cloud.fields.size ()))
00272           throw "The number of elements in <COUNT> differs than the number of elements in <FIELDS>!";
00273 
00274         field_counts.resize (specified_channel_count);
00275 
00276         int offset = 0;
00277         for (int i = 0; i < specified_channel_count; ++i)
00278         {
00279           cloud.fields[i].offset = offset;
00280           int col_count;
00281           sstream >> col_count;
00282           cloud.fields[i].count = col_count;
00283           offset += col_count * field_sizes[i];
00284         }
00285         // Adjust the offset for count (number of elements)
00286         cloud.point_step = offset;
00287         continue;
00288       }
00289 
00290       // Get the width of the data (organized point cloud dataset)
00291       if (line_type.substr (0, 5) == "WIDTH")
00292       {
00293         sstream >> cloud.width;
00294         if (cloud.point_step != 0)
00295           cloud.row_step = cloud.point_step * cloud.width;      // row_step only makes sense for organized datasets
00296         continue;
00297       }
00298 
00299       // Get the height of the data (organized point cloud dataset)
00300       if (line_type.substr (0, 6) == "HEIGHT")
00301       {
00302         sstream >> cloud.height;
00303         continue;
00304       }
00305 
00306       // Get the acquisition viewpoint
00307       if (line_type.substr (0, 9) == "VIEWPOINT")
00308       {
00309         pcd_version = PCD_V7;
00310         if (st.size () < 8)
00311           throw "Not enough number of elements in <VIEWPOINT>! Need 7 values (tx ty tz qw qx qy qz).";
00312 
00313         float x, y, z, w;
00314         sstream >> x >> y >> z ;
00315         origin      = Eigen::Vector4f (x, y, z, 0.0f);
00316         sstream >> w >> x >> y >> z;
00317         orientation = Eigen::Quaternionf (w, x, y, z);
00318         continue;
00319       }
00320 
00321       // Get the number of points
00322       if (line_type.substr (0, 6) == "POINTS")
00323       {
00324         sstream >> nr_points;
00325         // Need to allocate: N * point_step
00326         cloud.data.resize (nr_points * cloud.point_step);
00327         continue;
00328       }
00329 
00330       // Read the header + comments line by line until we get to <DATA>
00331       if (line_type.substr (0, 4) == "DATA")
00332       {
00333         data_idx = static_cast<int> (fs.tellg ());
00334         if (st.at (1).substr (0, 17) == "binary_compressed")
00335          data_type = 2;
00336         else
00337           if (st.at (1).substr (0, 6) == "binary")
00338             data_type = 1;
00339         continue;
00340       }
00341       break;
00342     }
00343   }
00344   catch (const char *exception)
00345   {
00346     PCL_ERROR ("[pcl::PCDReader::readHeader] %s\n", exception);
00347     fs.close ();
00348     return (-1);
00349   }
00350 
00351   // Exit early: if no points have been given, there's no sense to read or check anything anymore
00352   if (nr_points == 0)
00353   {
00354     PCL_ERROR ("[pcl::PCDReader::readHeader] No points to read\n");
00355     fs.close ();
00356     return (-1);
00357   }
00358   
00359   // Compatibility with older PCD file versions
00360   if (cloud.width == 0 && cloud.height == 0)
00361   {
00362     cloud.width  = nr_points;
00363     cloud.height = 1;
00364     cloud.row_step = cloud.point_step * cloud.width;      // row_step only makes sense for organized datasets
00365   }
00366   //assert (cloud.row_step != 0);       // If row_step = 0, either point_step was not set or width is 0
00367 
00368   // if both height/width are not given, assume an unorganized dataset
00369   if (cloud.height == 0)
00370   {
00371     cloud.height = 1;
00372     PCL_WARN ("[pcl::PCDReader::readHeader] no HEIGHT given, setting to 1 (unorganized).\n");
00373     if (cloud.width == 0)
00374       cloud.width  = nr_points;
00375   }
00376   else
00377   {
00378     if (cloud.width == 0 && nr_points != 0)
00379     {
00380       PCL_ERROR ("[pcl::PCDReader::readHeader] HEIGHT given (%d) but no WIDTH!\n", cloud.height);
00381       fs.close ();
00382       return (-1);
00383     }
00384   }
00385 
00386   if (int (cloud.width * cloud.height) != nr_points)
00387   {
00388     PCL_ERROR ("[pcl::PCDReader::readHeader] HEIGHT (%d) x WIDTH (%d) != number of points (%d)\n", cloud.height, cloud.width, nr_points);
00389     fs.close ();
00390     return (-1);
00391   }
00392 
00393   // Close file
00394   fs.close ();
00395 
00396   return (0);
00397 }
00398 
00400 int
00401 pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset)
00402 {
00403   // Default values
00404   cloud.width = cloud.height = cloud.point_step = cloud.row_step = 0;
00405   cloud.data.clear ();
00406 
00407   // By default, assume that there are _no_ invalid (e.g., NaN) points
00408   //cloud.is_dense = true;
00409 
00410   int nr_points = 0;
00411   std::ifstream fs;
00412   std::string line;
00413 
00414   int specified_channel_count = 0;
00415 
00416   if (file_name == "" || !boost::filesystem::exists (file_name))
00417   {
00418     PCL_ERROR ("[pcl::PCDReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
00419     return (-1);
00420   }
00421 
00422   // Open file in binary mode to avoid problem of 
00423   // std::getline() corrupting the result of ifstream::tellg()
00424   fs.open (file_name.c_str (), std::ios::binary);
00425   if (!fs.is_open () || fs.fail ())
00426   {
00427     PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror(errno)); 
00428     fs.close ();
00429     return (-1);
00430   }
00431 
00432   // Seek at the given offset
00433   fs.seekg (offset, std::ios::beg);
00434 
00435   // field_sizes represents the size of one element in a field (e.g., float = 4, char = 1)
00436   // field_counts represents the number of elements in a field (e.g., x = 1, normal_x = 1, fpfh = 33)
00437   std::vector<int> field_sizes, field_counts;
00438   // field_types represents the type of data in a field (e.g., F = float, U = unsigned)
00439   std::vector<char> field_types;
00440   std::vector<std::string> st;
00441 
00442   // Read the header and fill it in with wonderful values
00443   try
00444   {
00445     while (!fs.eof ())
00446     {
00447       getline (fs, line);
00448       // Ignore empty lines
00449       if (line == "")
00450         continue;
00451 
00452       // Tokenize the line
00453       boost::trim (line);
00454       boost::split (st, line, boost::is_any_of ("\t\r "), boost::token_compress_on);
00455 
00456       std::stringstream sstream (line);
00457       sstream.imbue (std::locale::classic ());
00458 
00459       std::string line_type;
00460       sstream >> line_type;
00461 
00462       // Ignore comments
00463       if (line_type.substr (0, 1) == "#")
00464         continue;
00465 
00466       // Version numbers are not needed for now, but we are checking to see if they're there
00467       if (line_type.substr (0, 7) == "VERSION")
00468         continue;
00469 
00470       // Get the field indices (check for COLUMNS too for backwards compatibility)
00471       if ( (line_type.substr (0, 6) == "FIELDS") || (line_type.substr (0, 7) == "COLUMNS") )
00472       {
00473         specified_channel_count = static_cast<int> (st.size () - 1);
00474 
00475         // Allocate enough memory to accommodate all fields
00476         cloud.fields.resize (specified_channel_count);
00477         for (int i = 0; i < specified_channel_count; ++i)
00478         {
00479           std::string col_type = st.at (i + 1);
00480           cloud.fields[i].name = col_type;
00481         }
00482 
00483         // Default the sizes and the types of each field to float32 to avoid crashes while using older PCD files
00484         int offset = 0;
00485         for (int i = 0; i < specified_channel_count; ++i, offset += 4)
00486         {
00487           cloud.fields[i].offset   = offset;
00488           cloud.fields[i].datatype = pcl::PCLPointField::FLOAT32;
00489           cloud.fields[i].count    = 1;
00490         }
00491         cloud.point_step = offset;
00492         continue;
00493       }
00494 
00495       // Get the field sizes
00496       if (line_type.substr (0, 4) == "SIZE")
00497       {
00498         specified_channel_count = static_cast<int> (st.size () - 1);
00499 
00500         // Allocate enough memory to accommodate all fields
00501         if (specified_channel_count != static_cast<int> (cloud.fields.size ()))
00502           throw "The number of elements in <SIZE> differs than the number of elements in <FIELDS>!";
00503 
00504         // Resize to accommodate the number of values
00505         field_sizes.resize (specified_channel_count);
00506 
00507         int offset = 0;
00508         for (int i = 0; i < specified_channel_count; ++i)
00509         {
00510           int col_type ;
00511           sstream >> col_type;
00512           cloud.fields[i].offset = offset;                // estimate and save the data offsets
00513           offset += col_type;
00514           field_sizes[i] = col_type;                      // save a temporary copy
00515         }
00516         cloud.point_step = offset;
00517         //if (cloud.width != 0)
00518           //cloud.row_step   = cloud.point_step * cloud.width;
00519         continue;
00520       }
00521 
00522       // Get the field types
00523       if (line_type.substr (0, 4) == "TYPE")
00524       {
00525         if (field_sizes.empty ())
00526           throw "TYPE of FIELDS specified before SIZE in header!";
00527 
00528         specified_channel_count = static_cast<int> (st.size () - 1);
00529 
00530         // Allocate enough memory to accommodate all fields
00531         if (specified_channel_count != static_cast<int> (cloud.fields.size ()))
00532           throw "The number of elements in <TYPE> differs than the number of elements in <FIELDS>!";
00533 
00534         // Resize to accommodate the number of values
00535         field_types.resize (specified_channel_count);
00536 
00537         for (int i = 0; i < specified_channel_count; ++i)
00538         {
00539           field_types[i] = st.at (i + 1).c_str ()[0];
00540           cloud.fields[i].datatype = static_cast<uint8_t> (getFieldType (field_sizes[i], field_types[i]));
00541         }
00542         continue;
00543       }
00544 
00545       // Get the field counts
00546       if (line_type.substr (0, 5) == "COUNT")
00547       {
00548         if (field_sizes.empty () || field_types.empty ())
00549           throw "COUNT of FIELDS specified before SIZE or TYPE in header!";
00550 
00551         specified_channel_count = static_cast<int> (st.size () - 1);
00552 
00553         // Allocate enough memory to accommodate all fields
00554         if (specified_channel_count != static_cast<int> (cloud.fields.size ()))
00555           throw "The number of elements in <COUNT> differs than the number of elements in <FIELDS>!";
00556 
00557         field_counts.resize (specified_channel_count);
00558 
00559         int offset = 0;
00560         for (int i = 0; i < specified_channel_count; ++i)
00561         {
00562           cloud.fields[i].offset = offset;
00563           int col_count;
00564           sstream >> col_count;
00565           cloud.fields[i].count = col_count;
00566           offset += col_count * field_sizes[i];
00567         }
00568         // Adjust the offset for count (number of elements)
00569         cloud.point_step = offset;
00570         continue;
00571       }
00572 
00573       // Get the width of the data (organized point cloud dataset)
00574       if (line_type.substr (0, 5) == "WIDTH")
00575       {
00576         sstream >> cloud.width;
00577         if (cloud.point_step != 0)
00578           cloud.row_step = cloud.point_step * cloud.width;      // row_step only makes sense for organized datasets
00579         continue;
00580       }
00581 
00582       // Get the height of the data (organized point cloud dataset)
00583       if (line_type.substr (0, 6) == "HEIGHT")
00584       {
00585         sstream >> cloud.height;
00586         continue;
00587       }
00588 
00589       // Check the format of the acquisition viewpoint
00590       if (line_type.substr (0, 9) == "VIEWPOINT")
00591       {
00592         if (st.size () < 8)
00593           throw "Not enough number of elements in <VIEWPOINT>! Need 7 values (tx ty tz qw qx qy qz).";
00594         continue;
00595       }
00596 
00597       // Get the number of points
00598       if (line_type.substr (0, 6) == "POINTS")
00599       {
00600         sstream >> nr_points;
00601         // Need to allocate: N * point_step
00602         cloud.data.resize (nr_points * cloud.point_step);
00603         continue;
00604       }
00605       break;
00606     }
00607   }
00608   catch (const char *exception)
00609   {
00610     PCL_ERROR ("[pcl::PCDReader::readHeader] %s\n", exception);
00611     fs.close ();
00612     return (-1);
00613   }
00614 
00615   // Exit early: if no points have been given, there's no sense to read or check anything anymore
00616   if (nr_points == 0)
00617   {
00618     PCL_ERROR ("[pcl::PCDReader::readHeader] No points to read\n");
00619     fs.close ();
00620     return (-1);
00621   }
00622   
00623   // Compatibility with older PCD file versions
00624   if (cloud.width == 0 && cloud.height == 0)
00625   {
00626     cloud.width  = nr_points;
00627     cloud.height = 1;
00628     cloud.row_step = cloud.point_step * cloud.width;      // row_step only makes sense for organized datasets
00629   }
00630   //assert (cloud.row_step != 0);       // If row_step = 0, either point_step was not set or width is 0
00631 
00632   // if both height/width are not given, assume an unorganized dataset
00633   if (cloud.height == 0)
00634   {
00635     cloud.height = 1;
00636     PCL_WARN ("[pcl::PCDReader::readHeader] no HEIGHT given, setting to 1 (unorganized).\n");
00637     if (cloud.width == 0)
00638       cloud.width  = nr_points;
00639   }
00640   else
00641   {
00642     if (cloud.width == 0 && nr_points != 0)
00643     {
00644       PCL_ERROR ("[pcl::PCDReader::readHeader] HEIGHT given (%d) but no WIDTH!\n", cloud.height);
00645       fs.close ();
00646       return (-1);
00647     }
00648   }
00649 
00650   if (int (cloud.width * cloud.height) != nr_points)
00651   {
00652     PCL_ERROR ("[pcl::PCDReader::readHeader] HEIGHT (%d) x WIDTH (%d) != number of points (%d)\n", cloud.height, cloud.width, nr_points);
00653     fs.close ();
00654     return (-1);
00655   }
00656 
00657   // Close file
00658   fs.close ();
00659 
00660   return (0);
00661 }
00662 
00664 int
00665 pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00666                       Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, 
00667                       const int offset)
00668 {
00669   pcl::console::TicToc tt;
00670   tt.tic ();
00671 
00672   int data_type;
00673   unsigned int data_idx;
00674 
00675   int res = readHeader (file_name, cloud, origin, orientation, pcd_version, data_type, data_idx, offset);
00676 
00677   if (res < 0)
00678     return (res);
00679 
00680   unsigned int idx = 0;
00681 
00682   // Get the number of points the cloud should have
00683   unsigned int nr_points = cloud.width * cloud.height;
00684 
00685   // Setting the is_dense property to true by default
00686   cloud.is_dense = true;
00687 
00688   if (file_name == "" || !boost::filesystem::exists (file_name))
00689   {
00690     PCL_ERROR ("[pcl::PCDReader::read] Could not find file '%s'.\n", file_name.c_str ());
00691     return (-1);
00692   }
00693   
00694   // if ascii
00695   if (data_type == 0)
00696   {
00697     // Re-open the file (readHeader closes it)
00698     std::ifstream fs;
00699     fs.open (file_name.c_str ());
00700     if (!fs.is_open () || fs.fail ())
00701     {
00702       PCL_ERROR ("[pcl::PCDReader::read] Could not open file %s.\n", file_name.c_str ());
00703       return (-1);
00704     }
00705 
00706     fs.seekg (data_idx);
00707 
00708     std::string line;
00709     std::vector<std::string> st;
00710 
00711     // Read the rest of the file
00712     try
00713     {
00714       while (idx < nr_points && !fs.eof ())
00715       {
00716         getline (fs, line);
00717         // Ignore empty lines
00718         if (line == "")
00719           continue;
00720 
00721         // Tokenize the line
00722         boost::trim (line);
00723         boost::split (st, line, boost::is_any_of ("\t\r "), boost::token_compress_on);
00724         
00725         if (idx >= nr_points)
00726         {
00727           PCL_WARN ("[pcl::PCDReader::read] input file %s has more points (%d) than advertised (%d)!\n", file_name.c_str (), idx, nr_points);
00728           break;
00729         }
00730 
00731         size_t total = 0;
00732         // Copy data
00733         for (unsigned int d = 0; d < static_cast<unsigned int> (cloud.fields.size ()); ++d)
00734         {
00735           // Ignore invalid padded dimensions that are inherited from binary data
00736           if (cloud.fields[d].name == "_")
00737           {
00738             total += cloud.fields[d].count; // jump over this many elements in the string token
00739             continue;
00740           }
00741           for (unsigned int c = 0; c < cloud.fields[d].count; ++c)
00742           {
00743             switch (cloud.fields[d].datatype)
00744             {
00745               case pcl::PCLPointField::INT8:
00746               {
00747                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::INT8>::type> (
00748                     st.at (total + c), cloud, idx, d, c);
00749                 break;
00750               }
00751               case pcl::PCLPointField::UINT8:
00752               {
00753                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::UINT8>::type> (
00754                     st.at (total + c), cloud, idx, d, c);
00755                 break;
00756               }
00757               case pcl::PCLPointField::INT16:
00758               {
00759                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::INT16>::type> (
00760                     st.at (total + c), cloud, idx, d, c);
00761                 break;
00762               }
00763               case pcl::PCLPointField::UINT16:
00764               {
00765                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::UINT16>::type> (
00766                     st.at (total + c), cloud, idx, d, c);
00767                 break;
00768               }
00769               case pcl::PCLPointField::INT32:
00770               {
00771                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::INT32>::type> (
00772                     st.at (total + c), cloud, idx, d, c);
00773                 break;
00774               }
00775               case pcl::PCLPointField::UINT32:
00776               {
00777                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::UINT32>::type> (
00778                     st.at (total + c), cloud, idx, d, c);
00779                 break;
00780               }
00781               case pcl::PCLPointField::FLOAT32:
00782               {
00783                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::FLOAT32>::type> (
00784                     st.at (total + c), cloud, idx, d, c);
00785                 break;
00786               }
00787               case pcl::PCLPointField::FLOAT64:
00788               {
00789                 copyStringValue<pcl::traits::asType<pcl::PCLPointField::FLOAT64>::type> (
00790                     st.at (total + c), cloud, idx, d, c);
00791                 break;
00792               }
00793               default:
00794                 PCL_WARN ("[pcl::PCDReader::read] Incorrect field data type specified (%d)!\n",cloud.fields[d].datatype);
00795                 break;
00796             }
00797           }
00798           total += cloud.fields[d].count; // jump over this many elements in the string token
00799         }
00800         idx++;
00801       }
00802     }
00803     catch (const char *exception)
00804     {
00805       PCL_ERROR ("[pcl::PCDReader::read] %s\n", exception);
00806       fs.close ();
00807       return (-1);
00808     }
00809 
00810     // Close file
00811     fs.close ();
00812   }
00813   else 
00816   {
00817     // Open for reading
00818     int fd = pcl_open (file_name.c_str (), O_RDONLY);
00819     if (fd == -1)
00820     {
00821       PCL_ERROR ("[pcl::PCDReader::read] Failure to open file %s\n", file_name.c_str () );
00822       return (-1);
00823     }
00824     
00825     // Seek at the given offset
00826     off_t result = pcl_lseek (fd, offset, SEEK_SET);
00827     if (result < 0)
00828     {
00829       pcl_close (fd);
00830       PCL_ERROR ("[pcl::PCDReader::read] lseek errno: %d strerror: %s\n", errno, strerror (errno));
00831       PCL_ERROR ("[pcl::PCDReader::read] Error during lseek ()!\n");
00832       return (-1);
00833     }
00834     
00835     size_t data_size = data_idx + cloud.data.size ();
00836     // Prepare the map
00837 #ifdef _WIN32
00838     // As we don't know the real size of data (compressed or not), 
00839     // we set dwMaximumSizeHigh = dwMaximumSizeLow = 0 so as to map the whole file
00840     HANDLE fm = CreateFileMapping ((HANDLE) _get_osfhandle (fd), NULL, PAGE_READONLY, 0, 0, NULL);
00841     // As we don't know the real size of data (compressed or not), 
00842     // we set dwNumberOfBytesToMap = 0 so as to map the whole file
00843     char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ, 0, 0, 0));
00844     if (map == NULL)
00845     {
00846       CloseHandle (fm);
00847       pcl_close (fd);
00848       PCL_ERROR ("[pcl::PCDReader::read] Error mapping view of file, %s\n", file_name.c_str ());
00849       return (-1);
00850     }
00851 #else
00852     char *map = static_cast<char*> (mmap (0, data_size, PROT_READ, MAP_SHARED, fd, 0));
00853     if (map == reinterpret_cast<char*> (-1))    // MAP_FAILED
00854     {
00855       pcl_close (fd);
00856       PCL_ERROR ("[pcl::PCDReader::read] Error preparing mmap for binary PCD file.\n");
00857       return (-1);
00858     }
00859 #endif
00860 
00862     if (data_type == 2)
00863     {
00864       // Uncompress the data first
00865       unsigned int compressed_size, uncompressed_size;
00866       memcpy (&compressed_size, &map[data_idx + 0], sizeof (unsigned int));
00867       memcpy (&uncompressed_size, &map[data_idx + 4], sizeof (unsigned int));
00868       PCL_DEBUG ("[pcl::PCDReader::read] Read a binary compressed file with %u bytes compressed and %u original.\n", compressed_size, uncompressed_size);
00869       // For all those weird situations where the compressed data is actually LARGER than the uncompressed one
00870       // (we really ought to check this in the compressor and copy the original data in those cases)
00871       if (data_size < compressed_size || uncompressed_size < compressed_size)
00872       {
00873         PCL_DEBUG ("[pcl::PCDReader::read] Allocated data size (%zu) or uncompressed size (%zu) smaller than compressed size (%u). Need to remap.\n", data_size, uncompressed_size, compressed_size);
00874 #ifdef _WIN32
00875         UnmapViewOfFile (map);
00876         data_size = compressed_size + data_idx + 8;
00877         map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ, 0, 0, data_size));
00878 #else
00879         munmap (map, data_size);
00880         data_size = compressed_size + data_idx + 8;
00881         map = static_cast<char*> (mmap (0, data_size, PROT_READ, MAP_SHARED, fd, 0));
00882 #endif
00883       }
00884 
00885       if (uncompressed_size != cloud.data.size ())
00886       {
00887         PCL_WARN ("[pcl::PCDReader::read] The estimated cloud.data size (%u) is different than the saved uncompressed value (%u)! Data corruption?\n", 
00888                   cloud.data.size (), uncompressed_size);
00889         cloud.data.resize (uncompressed_size);
00890       }
00891 
00892       char *buf = static_cast<char*> (malloc (data_size));
00893       // The size of the uncompressed data better be the same as what we stored in the header
00894       unsigned int tmp_size = pcl::lzfDecompress (&map[data_idx + 8], compressed_size, buf, static_cast<unsigned int> (data_size));
00895       if (tmp_size != uncompressed_size)
00896       {
00897         free (buf);
00898         pcl_close (fd);
00899         PCL_ERROR ("[pcl::PCDReader::read] Size of decompressed lzf data (%u) does not match value stored in PCD header (%u). Errno: %d\n", tmp_size, uncompressed_size, errno);
00900         return (-1);
00901       }
00902 
00903       // Get the fields sizes
00904       std::vector<pcl::PCLPointField> fields (cloud.fields.size ());
00905       std::vector<int> fields_sizes (cloud.fields.size ());
00906       int nri = 0, fsize = 0;
00907       for (size_t i = 0; i < cloud.fields.size (); ++i)
00908       {
00909         if (cloud.fields[i].name == "_")
00910           continue;
00911         fields_sizes[nri] = cloud.fields[i].count * pcl::getFieldSize (cloud.fields[i].datatype);
00912         fsize += fields_sizes[nri];
00913         fields[nri] = cloud.fields[i];
00914         ++nri;
00915       }
00916       fields.resize (nri);
00917       fields_sizes.resize (nri);
00918 
00919       // Unpack the xxyyzz to xyz
00920       std::vector<char*> pters (fields.size ());
00921       int toff = 0;
00922       for (size_t i = 0; i < pters.size (); ++i)
00923       {
00924         pters[i] = &buf[toff];
00925         toff += fields_sizes[i] * cloud.width * cloud.height;
00926       }
00927       // Copy it to the cloud
00928       for (size_t i = 0; i < cloud.width * cloud.height; ++i)
00929       {
00930         for (size_t j = 0; j < pters.size (); ++j)
00931         {
00932           memcpy (&cloud.data[i * fsize + fields[j].offset], pters[j], fields_sizes[j]);
00933           // Increment the pointer
00934           pters[j] += fields_sizes[j];
00935         }
00936       }
00937       //memcpy (&cloud.data[0], &buf[0], uncompressed_size);
00938 
00939       free (buf);
00940     }
00941     else
00942       // Copy the data
00943       memcpy (&cloud.data[0], &map[0] + data_idx, cloud.data.size ());
00944 
00945     // Unmap the pages of memory
00946 #ifdef _WIN32
00947     UnmapViewOfFile (map);
00948     CloseHandle (fm);
00949 #else
00950     if (munmap (map, data_size) == -1)
00951     {
00952       pcl_close (fd);
00953       PCL_ERROR ("[pcl::PCDReader::read] Munmap failure\n");
00954       return (-1);
00955     }
00956 #endif
00957     pcl_close (fd);
00958   }
00959 
00960   if ((idx != nr_points) && (data_type == 0))
00961   {
00962     PCL_ERROR ("[pcl::PCDReader::read] Number of points read (%d) is different than expected (%d)\n", idx, nr_points);
00963     return (-1);
00964   }
00965 
00966   // No need to do any extra checks if the data type is ASCII
00967   if (data_type != 0)
00968   {
00969     int point_size = static_cast<int> (cloud.data.size () / (cloud.height * cloud.width));
00970     // Once copied, we need to go over each field and check if it has NaN/Inf values and assign cloud.is_dense to true or false
00971     for (uint32_t i = 0; i < cloud.width * cloud.height; ++i)
00972     {
00973       for (unsigned int d = 0; d < static_cast<unsigned int> (cloud.fields.size ()); ++d)
00974       {
00975         for (uint32_t c = 0; c < cloud.fields[d].count; ++c)
00976         {
00977           switch (cloud.fields[d].datatype)
00978           {
00979             case pcl::PCLPointField::INT8:
00980             {
00981               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::INT8>::type>(cloud, i, point_size, d, c))
00982                 cloud.is_dense = false;
00983               break;
00984             }
00985             case pcl::PCLPointField::UINT8:
00986             {
00987               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::UINT8>::type>(cloud, i, point_size, d, c))
00988                 cloud.is_dense = false;
00989               break;
00990             }
00991             case pcl::PCLPointField::INT16:
00992             {
00993               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::INT16>::type>(cloud, i, point_size, d, c))
00994                 cloud.is_dense = false;
00995               break;
00996             }
00997             case pcl::PCLPointField::UINT16:
00998             {
00999               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::UINT16>::type>(cloud, i, point_size, d, c))
01000                 cloud.is_dense = false;
01001               break;
01002             }
01003             case pcl::PCLPointField::INT32:
01004             {
01005               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::INT32>::type>(cloud, i, point_size, d, c))
01006                 cloud.is_dense = false;
01007               break;
01008             }
01009             case pcl::PCLPointField::UINT32:
01010             {
01011               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::UINT32>::type>(cloud, i, point_size, d, c))
01012                 cloud.is_dense = false;
01013               break;
01014             }
01015             case pcl::PCLPointField::FLOAT32:
01016             {
01017               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::FLOAT32>::type>(cloud, i, point_size, d, c))
01018                 cloud.is_dense = false;
01019               break;
01020             }
01021             case pcl::PCLPointField::FLOAT64:
01022             {
01023               if (!isValueFinite<pcl::traits::asType<pcl::PCLPointField::FLOAT64>::type>(cloud, i, point_size, d, c))
01024                 cloud.is_dense = false;
01025               break;
01026             }
01027           }
01028         }
01029       }
01030     }
01031   }
01032   double total_time = tt.toc ();
01033   PCL_DEBUG ("[pcl::PCDReader::read] Loaded %s as a %s cloud in %g ms with %d points. Available dimensions: %s.\n", 
01034              file_name.c_str (), cloud.is_dense ? "dense" : "non-dense", total_time, 
01035              cloud.width * cloud.height, pcl::getFieldsList (cloud).c_str ());
01036   return (0);
01037 }
01038 
01040 int
01041 pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset)
01042 {
01043   int pcd_version;
01044   Eigen::Vector4f origin;
01045   Eigen::Quaternionf orientation;
01046   // Load the data
01047   int res = read (file_name, cloud, origin, orientation, pcd_version, offset);
01048 
01049   if (res < 0)
01050     return (res);
01051 
01052   return (0);
01053 }
01054 
01056 std::string
01057 pcl::PCDWriter::generateHeaderASCII (const pcl::PCLPointCloud2 &cloud,
01058                                      const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
01059 {
01060   std::ostringstream oss;
01061   oss.imbue (std::locale::classic ());
01062 
01063   oss << "# .PCD v0.7 - Point Cloud Data file format"
01064          "\nVERSION 0.7"
01065          "\nFIELDS ";
01066 
01067   std::ostringstream stream;
01068   stream.imbue (std::locale::classic ());
01069   std::string result;
01070 
01071   for (size_t d = 0; d < cloud.fields.size () - 1; ++d)
01072   {
01073     // Ignore invalid padded dimensions that are inherited from binary data
01074     if (cloud.fields[d].name != "_")
01075       result += cloud.fields[d].name + " ";
01076   }
01077   // Ignore invalid padded dimensions that are inherited from binary data
01078   if (cloud.fields[cloud.fields.size () - 1].name != "_")
01079     result += cloud.fields[cloud.fields.size () - 1].name;
01080 
01081   // Remove trailing spaces
01082   boost::trim (result);
01083   oss << result << "\nSIZE ";
01084 
01085   stream.str ("");
01086   // Write the SIZE of each field
01087   for (size_t d = 0; d < cloud.fields.size () - 1; ++d)
01088   {
01089     // Ignore invalid padded dimensions that are inherited from binary data
01090     if (cloud.fields[d].name != "_")
01091       stream << pcl::getFieldSize (cloud.fields[d].datatype) << " ";
01092   }
01093   // Ignore invalid padded dimensions that are inherited from binary data
01094   if (cloud.fields[cloud.fields.size () - 1].name != "_")
01095     stream << pcl::getFieldSize (cloud.fields[cloud.fields.size () - 1].datatype);
01096 
01097   // Remove trailing spaces
01098   result = stream.str ();
01099   boost::trim (result);
01100   oss << result << "\nTYPE ";
01101 
01102   stream.str ("");
01103   // Write the TYPE of each field
01104   for (size_t d = 0; d < cloud.fields.size () - 1; ++d)
01105   {
01106     // Ignore invalid padded dimensions that are inherited from binary data
01107     if (cloud.fields[d].name != "_")
01108       stream << pcl::getFieldType (cloud.fields[d].datatype) << " ";
01109   }
01110   // Ignore invalid padded dimensions that are inherited from binary data
01111   if (cloud.fields[cloud.fields.size () - 1].name != "_")
01112     stream << pcl::getFieldType (cloud.fields[cloud.fields.size () - 1].datatype);
01113 
01114   // Remove trailing spaces
01115   result = stream.str ();
01116   boost::trim (result);
01117   oss << result << "\nCOUNT ";
01118   
01119   stream.str ("");
01120   // Write the TYPE of each field
01121   for (size_t d = 0; d < cloud.fields.size () - 1; ++d)
01122   {
01123     // Ignore invalid padded dimensions that are inherited from binary data
01124     if (cloud.fields[d].name == "_")
01125       continue;
01126     int count = abs (static_cast<int> (cloud.fields[d].count));
01127     if (count == 0) 
01128       count = 1;          // we simply cannot tolerate 0 counts (coming from older converter code)
01129   
01130     stream << count << " ";
01131   }
01132   // Ignore invalid padded dimensions that are inherited from binary data
01133   if (cloud.fields[cloud.fields.size () - 1].name != "_")
01134   {
01135     int count = abs (static_cast<int> (cloud.fields[cloud.fields.size () - 1].count));
01136     if (count == 0)
01137       count = 1;
01138 
01139     stream << count;
01140   }
01141 
01142   // Remove trailing spaces
01143   result = stream.str ();
01144   boost::trim (result);
01145   oss << result << "\nWIDTH " << cloud.width << "\nHEIGHT " << cloud.height << "\n";
01146 
01147   oss << "VIEWPOINT " << origin[0] << " " << origin[1] << " " << origin[2] << " " << orientation.w () << " " << 
01148                          orientation.x () << " " << orientation.y () << " " << orientation.z () << "\n";
01149   
01150   oss << "POINTS " << cloud.width * cloud.height << "\n";
01151 
01152   return (oss.str ());
01153 }
01154 
01156 std::string
01157 pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud,
01158                                       const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
01159 {
01160   std::ostringstream oss;
01161   oss.imbue (std::locale::classic ());
01162 
01163   oss << "# .PCD v0.7 - Point Cloud Data file format"
01164          "\nVERSION 0.7"
01165          "\nFIELDS";
01166 
01167   // Compute the total size of the fields
01168   unsigned int fsize = 0;
01169   for (size_t i = 0; i < cloud.fields.size (); ++i)
01170     fsize += cloud.fields[i].count * getFieldSize (cloud.fields[i].datatype);
01171  
01172   // The size of the fields cannot be larger than point_step
01173   if (fsize > cloud.point_step)
01174   {
01175     PCL_ERROR ("[pcl::PCDWriter::generateHeaderBinary] The size of the fields (%d) is larger than point_step (%d)! Something is wrong here...\n", fsize, cloud.point_step);
01176     return ("");
01177   }
01178 
01179   std::stringstream field_names, field_types, field_sizes, field_counts;
01180   // Check if the size of the fields is smaller than the size of the point step
01181   unsigned int toffset = 0;
01182   for (size_t i = 0; i < cloud.fields.size (); ++i)
01183   {
01184     // If field offsets do not match, then we need to create fake fields
01185     if (toffset != cloud.fields[i].offset)
01186     {
01187       // If we're at the last "valid" field
01188       int fake_offset = (i == 0) ? 
01189         // Use the current_field offset
01190         (cloud.fields[i].offset)
01191         :
01192         // Else, do cur_field.offset - prev_field.offset + sizeof (prev_field)
01193         (cloud.fields[i].offset - 
01194         (cloud.fields[i-1].offset + 
01195          cloud.fields[i-1].count * getFieldSize (cloud.fields[i].datatype)));
01196       
01197       toffset += fake_offset;
01198 
01199       field_names << " _";  // By convention, _ is an invalid field name
01200       field_sizes << " 1";  // Make size = 1
01201       field_types << " U";  // Field type = unsigned byte (uint8)
01202       field_counts << " " << fake_offset;
01203     }
01204 
01205     // Add the regular dimension
01206     toffset += cloud.fields[i].count * getFieldSize (cloud.fields[i].datatype);
01207     field_names << " " << cloud.fields[i].name;
01208     field_sizes << " " << pcl::getFieldSize (cloud.fields[i].datatype);
01209     field_types << " " << pcl::getFieldType (cloud.fields[i].datatype);
01210     int count = abs (static_cast<int> (cloud.fields[i].count));
01211     if (count == 0) count = 1;  // check for 0 counts (coming from older converter code)
01212     field_counts << " " << count;
01213   }
01214   // Check extra padding
01215   if (toffset < cloud.point_step)
01216   {
01217     field_names << " _";  // By convention, _ is an invalid field name
01218     field_sizes << " 1";  // Make size = 1
01219     field_types << " U";  // Field type = unsigned byte (uint8)
01220     field_counts << " " << (cloud.point_step - toffset);
01221   }
01222   oss << field_names.str ();
01223   oss << "\nSIZE" << field_sizes.str () 
01224       << "\nTYPE" << field_types.str () 
01225       << "\nCOUNT" << field_counts.str ();
01226   oss << "\nWIDTH " << cloud.width << "\nHEIGHT " << cloud.height << "\n";
01227 
01228   oss << "VIEWPOINT " << origin[0] << " " << origin[1] << " " << origin[2] << " " << orientation.w () << " " << 
01229                          orientation.x () << " " << orientation.y () << " " << orientation.z () << "\n";
01230   
01231   oss << "POINTS " << cloud.width * cloud.height << "\n";
01232 
01233   return (oss.str ());
01234 }
01235 
01237 std::string
01238 pcl::PCDWriter::generateHeaderBinaryCompressed (const pcl::PCLPointCloud2 &cloud,
01239                                                 const Eigen::Vector4f &origin, 
01240                                                 const Eigen::Quaternionf &orientation)
01241 {
01242   std::ostringstream oss;
01243   oss.imbue (std::locale::classic ());
01244 
01245   oss << "# .PCD v0.7 - Point Cloud Data file format"
01246          "\nVERSION 0.7"
01247          "\nFIELDS";
01248 
01249   // Compute the total size of the fields
01250   unsigned int fsize = 0;
01251   for (size_t i = 0; i < cloud.fields.size (); ++i)
01252     fsize += cloud.fields[i].count * getFieldSize (cloud.fields[i].datatype);
01253  
01254   // The size of the fields cannot be larger than point_step
01255   if (fsize > cloud.point_step)
01256   {
01257     PCL_ERROR ("[pcl::PCDWriter::generateHeaderBinaryCompressed] The size of the fields (%d) is larger than point_step (%d)! Something is wrong here...\n", fsize, cloud.point_step);
01258     return ("");
01259   }
01260 
01261   std::stringstream field_names, field_types, field_sizes, field_counts;
01262   // Check if the size of the fields is smaller than the size of the point step
01263   for (size_t i = 0; i < cloud.fields.size (); ++i)
01264   {
01265     if (cloud.fields[i].name == "_")
01266       continue;
01267     // Add the regular dimension
01268     field_names << " " << cloud.fields[i].name;
01269     field_sizes << " " << pcl::getFieldSize (cloud.fields[i].datatype);
01270     field_types << " " << pcl::getFieldType (cloud.fields[i].datatype);
01271     int count = abs (static_cast<int> (cloud.fields[i].count));
01272     if (count == 0) count = 1;  // check for 0 counts (coming from older converter code)
01273     field_counts << " " << count;
01274   }
01275   oss << field_names.str ();
01276   oss << "\nSIZE" << field_sizes.str () 
01277       << "\nTYPE" << field_types.str () 
01278       << "\nCOUNT" << field_counts.str ();
01279   oss << "\nWIDTH " << cloud.width << "\nHEIGHT " << cloud.height << "\n";
01280 
01281   oss << "VIEWPOINT " << origin[0] << " " << origin[1] << " " << origin[2] << " " << orientation.w () << " " << 
01282                          orientation.x () << " " << orientation.y () << " " << orientation.z () << "\n";
01283   
01284   oss << "POINTS " << cloud.width * cloud.height << "\n";
01285 
01286   return (oss.str ());
01287 }
01288 
01290 int
01291 pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
01292                             const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation,
01293                             const int precision)
01294 {
01295   if (cloud.data.empty ())
01296   {
01297     PCL_ERROR ("[pcl::PCDWriter::writeASCII] Input point cloud has no data!\n");
01298     return (-1);
01299   }
01300 
01301   std::ofstream fs;
01302   fs.precision (precision);
01303   fs.imbue (std::locale::classic ());
01304   fs.open (file_name.c_str ());      // Open file
01305   if (!fs.is_open () || fs.fail ())
01306   {
01307     PCL_ERROR("[pcl::PCDWriter::writeASCII] Could not open file '%s' for writing! Error : %s\n", file_name.c_str (), strerror(errno)); 
01308     return (-1);
01309   }
01310   // Mandatory lock file
01311   boost::interprocess::file_lock file_lock;
01312   setLockingPermissions (file_name, file_lock);
01313 
01314   int nr_points  = cloud.width * cloud.height;
01315   int point_size = static_cast<int> (cloud.data.size () / nr_points);
01316 
01317   // Write the header information
01318   fs << generateHeaderASCII (cloud, origin, orientation) << "DATA ascii\n";
01319 
01320   std::ostringstream stream;
01321   stream.precision (precision);
01322   stream.imbue (std::locale::classic ());
01323 
01324   // Iterate through the points
01325   for (int i = 0; i < nr_points; ++i)
01326   {
01327     for (unsigned int d = 0; d < static_cast<unsigned int> (cloud.fields.size ()); ++d)
01328     {
01329       // Ignore invalid padded dimensions that are inherited from binary data
01330       if (cloud.fields[d].name == "_")
01331         continue;
01332 
01333       int count = cloud.fields[d].count;
01334       if (count == 0) 
01335         count = 1;          // we simply cannot tolerate 0 counts (coming from older converter code)
01336 
01337       for (int c = 0; c < count; ++c)
01338       {
01339         switch (cloud.fields[d].datatype)
01340         {
01341           case pcl::PCLPointField::INT8:
01342           {
01343             copyValueString<pcl::traits::asType<pcl::PCLPointField::INT8>::type>(cloud, i, point_size, d, c, stream);
01344             break;
01345           }
01346           case pcl::PCLPointField::UINT8:
01347           {
01348             copyValueString<pcl::traits::asType<pcl::PCLPointField::UINT8>::type>(cloud, i, point_size, d, c, stream);
01349             break;
01350           }
01351           case pcl::PCLPointField::INT16:
01352           {
01353             copyValueString<pcl::traits::asType<pcl::PCLPointField::INT16>::type>(cloud, i, point_size, d, c, stream);
01354             break;
01355           }
01356           case pcl::PCLPointField::UINT16:
01357           {
01358             copyValueString<pcl::traits::asType<pcl::PCLPointField::UINT16>::type>(cloud, i, point_size, d, c, stream);
01359             break;
01360           }
01361           case pcl::PCLPointField::INT32:
01362           {
01363             copyValueString<pcl::traits::asType<pcl::PCLPointField::INT32>::type>(cloud, i, point_size, d, c, stream);
01364             break;
01365           }
01366           case pcl::PCLPointField::UINT32:
01367           {
01368             copyValueString<pcl::traits::asType<pcl::PCLPointField::UINT32>::type>(cloud, i, point_size, d, c, stream);
01369             break;
01370           }
01371           case pcl::PCLPointField::FLOAT32:
01372           {
01373             copyValueString<pcl::traits::asType<pcl::PCLPointField::FLOAT32>::type>(cloud, i, point_size, d, c, stream);
01374             break;
01375           }
01376           case pcl::PCLPointField::FLOAT64:
01377           {
01378             copyValueString<pcl::traits::asType<pcl::PCLPointField::FLOAT64>::type>(cloud, i, point_size, d, c, stream);
01379             break;
01380           }
01381           default:
01382             PCL_WARN ("[pcl::PCDWriter::writeASCII] Incorrect field data type specified (%d)!\n", cloud.fields[d].datatype);
01383             break;
01384         }
01385 
01386         if (d < cloud.fields.size () - 1 || c < static_cast<int> (cloud.fields[d].count) - 1)
01387           stream << " ";
01388       }
01389     }
01390     // Copy the stream, trim it, and write it to disk
01391     std::string result = stream.str ();
01392     boost::trim (result);
01393     stream.str ("");
01394     fs << result << "\n";
01395   }
01396   fs.close ();              // Close file
01397   resetLockingPermissions (file_name, file_lock);
01398   return (0);
01399 }
01400 
01402 int
01403 pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
01404                              const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
01405 {
01406   if (cloud.data.empty ())
01407   {
01408     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!\n");
01409     return (-1);
01410   }
01411   std::streamoff data_idx = 0;
01412   std::ostringstream oss;
01413   oss.imbue (std::locale::classic ());
01414 
01415   oss << generateHeaderBinary (cloud, origin, orientation) << "DATA binary\n";
01416   oss.flush();
01417   data_idx = static_cast<unsigned int> (oss.tellp ());
01418 
01419 #ifdef _WIN32
01420   HANDLE h_native_file = CreateFile (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
01421   if (h_native_file == INVALID_HANDLE_VALUE)
01422   {
01423     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Error during CreateFile (%s)!\n", file_name.c_str());
01424     return (-1);
01425   }
01426   // Mandatory lock file
01427   boost::interprocess::file_lock file_lock;
01428   setLockingPermissions (file_name, file_lock);
01429 
01430 #else
01431   int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast<mode_t> (0600));
01432   if (fd < 0)
01433   {
01434     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Error during open (%s)!\n", file_name.c_str());
01435     return (-1);
01436   }
01437   // Mandatory lock file
01438   boost::interprocess::file_lock file_lock;
01439   setLockingPermissions (file_name, file_lock);
01440 
01441   // Stretch the file size to the size of the data
01442   off_t result = pcl_lseek (fd, getpagesize () + cloud.data.size () - 1, SEEK_SET);
01443   if (result < 0)
01444   {
01445     pcl_close (fd);
01446     resetLockingPermissions (file_name, file_lock);
01447     PCL_ERROR ("[pcl::PCDWriter::writeBinary] lseek errno: %d strerror: %s\n", errno, strerror (errno));
01448     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Error during lseek ()!\n");
01449     return (-1);
01450   }
01451   // Write a bogus entry so that the new file size comes in effect
01452   result = static_cast<int> (::write (fd, "", 1));
01453   if (result != 1)
01454   {
01455     pcl_close (fd);
01456     resetLockingPermissions (file_name, file_lock);
01457     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Error during write ()!\n");
01458     return (-1);
01459   }
01460 #endif
01461   // Prepare the map
01462 #ifdef _WIN32
01463   HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + cloud.data.size ()), NULL);
01464   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + cloud.data.size ()));
01465   CloseHandle (fm);
01466 
01467 #else
01468   char *map = static_cast<char*> (mmap (0, static_cast<size_t> (data_idx + cloud.data.size ()), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0));
01469   if (map == reinterpret_cast<char*> (-1))    // MAP_FAILED
01470   {
01471     pcl_close (fd);
01472     resetLockingPermissions (file_name, file_lock);
01473     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Error during mmap ()!\n");
01474     return (-1);
01475   }
01476 #endif
01477 
01478   // copy header
01479   memcpy (&map[0], oss.str().c_str (), static_cast<size_t> (data_idx));
01480 
01481   // Copy the data
01482   memcpy (&map[0] + data_idx, &cloud.data[0], cloud.data.size ());
01483 
01484 #ifndef _WIN32
01485   // If the user set the synchronization flag on, call msync
01486   if (map_synchronization_)
01487     msync (map, static_cast<size_t> (data_idx + cloud.data.size ()), MS_SYNC);
01488 #endif
01489 
01490   // Unmap the pages of memory
01491 #ifdef _WIN32
01492     UnmapViewOfFile (map);
01493 #else
01494   if (munmap (map, static_cast<size_t> (data_idx + cloud.data.size ())) == -1)
01495   {
01496     pcl_close (fd);
01497     resetLockingPermissions (file_name, file_lock);
01498     PCL_ERROR ("[pcl::PCDWriter::writeBinary] Error during munmap ()!\n");
01499     return (-1);
01500   }
01501 #endif
01502   // Close file
01503 #ifdef _WIN32
01504   CloseHandle(h_native_file);
01505 #else
01506   pcl_close (fd);
01507 #endif
01508   resetLockingPermissions (file_name, file_lock);
01509   return (0);
01510 }
01511 
01513 int
01514 pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
01515                                        const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
01516 {
01517   if (cloud.data.empty ())
01518   {
01519     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Input point cloud has no data!\n");
01520     return (-1);
01521   }
01522   std::streamoff data_idx = 0;
01523   std::ostringstream oss;
01524   oss.imbue (std::locale::classic ());
01525 
01526   oss << generateHeaderBinaryCompressed (cloud, origin, orientation) << "DATA binary_compressed\n";
01527   oss.flush ();
01528   data_idx = oss.tellp ();
01529 
01530 #ifdef _WIN32
01531   HANDLE h_native_file = CreateFile (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
01532   if (h_native_file == INVALID_HANDLE_VALUE)
01533   {
01534     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Error during CreateFile (%s)!\n", file_name.c_str ());
01535     return (-1);
01536   }
01537 #else
01538   int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast<mode_t> (0600));
01539   if (fd < 0)
01540   {
01541     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Error during open (%s)!\n", file_name.c_str());
01542     return (-1);
01543   }
01544 #endif
01545   // Mandatory lock file
01546   boost::interprocess::file_lock file_lock;
01547   setLockingPermissions (file_name, file_lock);
01548 
01549   size_t fsize = 0;
01550   size_t data_size = 0;
01551   size_t nri = 0;
01552   std::vector<pcl::PCLPointField> fields (cloud.fields.size ());
01553   std::vector<int> fields_sizes (cloud.fields.size ());
01554   // Compute the total size of the fields
01555   for (size_t i = 0; i < cloud.fields.size (); ++i)
01556   {
01557     if (cloud.fields[i].name == "_")
01558       continue;
01559     
01560     fields_sizes[nri] = cloud.fields[i].count * pcl::getFieldSize (cloud.fields[i].datatype);
01561     fsize += fields_sizes[nri];
01562     fields[nri] = cloud.fields[i];
01563     ++nri;
01564   }
01565   fields_sizes.resize (nri);
01566   fields.resize (nri);
01567  
01568   // Compute the size of data
01569   data_size = cloud.width * cloud.height * fsize;
01570 
01572   // Empty array holding only the valid data
01573   // data_size = nr_points * point_size 
01574   //           = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n)
01575   //           = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ... sizeof_field_n * nr_points
01576   char *only_valid_data = static_cast<char*> (malloc (data_size));
01577 
01578   // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For
01579   // this, we need a vector of fields.size () (4 in this case), which points to
01580   // each individual plane:
01581   //   pters[0] = &only_valid_data[offset_of_plane_x];
01582   //   pters[1] = &only_valid_data[offset_of_plane_y];
01583   //   pters[2] = &only_valid_data[offset_of_plane_z];
01584   //   pters[3] = &only_valid_data[offset_of_plane_RGB];
01585   //
01586   std::vector<char*> pters (fields.size ());
01587   int toff = 0;
01588   for (size_t i = 0; i < pters.size (); ++i)
01589   {
01590     pters[i] = &only_valid_data[toff];
01591     toff += fields_sizes[i] * cloud.width * cloud.height;
01592   }
01593   
01594   // Go over all the points, and copy the data in the appropriate places
01595   for (size_t i = 0; i < cloud.width * cloud.height; ++i)
01596   {
01597     for (size_t j = 0; j < pters.size (); ++j)
01598     {
01599       memcpy (pters[j], &cloud.data[i * cloud.point_step + fields[j].offset], fields_sizes[j]);
01600       // Increment the pointer
01601       pters[j] += fields_sizes[j];
01602     }
01603   }
01604 
01605   char* temp_buf = static_cast<char*> (malloc (static_cast<size_t> (static_cast<float> (data_size) * 1.5f + 8.0f)));
01606   // Compress the valid data
01607   unsigned int compressed_size = pcl::lzfCompress (only_valid_data, 
01608                                                    static_cast<unsigned int> (data_size), 
01609                                                    &temp_buf[8], 
01610                                                    static_cast<unsigned int> (static_cast<float> (data_size) * 1.5f));
01611   unsigned int compressed_final_size = 0;
01612   // Was the compression successful?
01613   if (compressed_size)
01614   {
01615     char *header = &temp_buf[0];
01616     memcpy (&header[0], &compressed_size, sizeof (unsigned int));
01617     memcpy (&header[4], &data_size, sizeof (unsigned int));
01618     data_size = compressed_size + 8;
01619     compressed_final_size = static_cast<unsigned int> (data_size + data_idx);
01620   }
01621   else
01622   {
01623 #ifndef _WIN32
01624     pcl_close (fd);
01625 #endif
01626     resetLockingPermissions (file_name, file_lock);
01627     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during compression!");
01628     return (-1);
01629   }
01630 
01631 #ifndef _WIN32
01632   // Stretch the file size to the size of the data
01633   off_t result = pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET);
01634   if (result < 0)
01635   {
01636     pcl_close (fd);
01637     resetLockingPermissions (file_name, file_lock);
01638     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] lseek errno: %d strerror: %s\n", errno, strerror (errno));
01639     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Error during lseek ()!\n");
01640     return (-1);
01641   }
01642   // Write a bogus entry so that the new file size comes in effect
01643   result = static_cast<int> (::write (fd, "", 1));
01644   if (result != 1)
01645   {
01646     pcl_close (fd);
01647     resetLockingPermissions (file_name, file_lock);
01648     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Error during write ()!\n");
01649     return (-1);
01650   }
01651 #endif
01652 
01653   // Prepare the map
01654 #ifdef _WIN32
01655   HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, compressed_final_size, NULL);
01656   char *map = static_cast<char*> (MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, compressed_final_size));
01657   CloseHandle (fm);
01658 
01659 #else
01660   char *map = static_cast<char*> (mmap (0, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0));
01661   if (map == reinterpret_cast<char*> (-1))    // MAP_FAILED
01662   {
01663     pcl_close (fd);
01664     resetLockingPermissions (file_name, file_lock);
01665     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Error during mmap ()!\n");
01666     return (-1);
01667   }
01668 #endif
01669 
01670   // copy header
01671   memcpy (&map[0], oss.str ().c_str (), static_cast<size_t> (data_idx));
01672   // Copy the compressed data
01673   memcpy (&map[data_idx], temp_buf, data_size);
01674 
01675 #ifndef _WIN32
01676   // If the user set the synchronization flag on, call msync
01677   if (map_synchronization_)
01678     msync (map, compressed_final_size, MS_SYNC);
01679 #endif
01680 
01681   // Unmap the pages of memory
01682 #ifdef _WIN32
01683     UnmapViewOfFile (map);
01684 #else
01685   if (munmap (map, (compressed_final_size)) == -1)
01686   {
01687     pcl_close (fd);
01688     resetLockingPermissions (file_name, file_lock);
01689     PCL_ERROR ("[pcl::PCDWriter::writeBinaryCompressed] Error during munmap ()!\n");
01690     return (-1);
01691   }
01692 #endif
01693   // Close file
01694 #ifdef _WIN32
01695   CloseHandle (h_native_file);
01696 #else
01697   pcl_close (fd);
01698 #endif
01699   resetLockingPermissions (file_name, file_lock);
01700 
01701   free (only_valid_data);
01702   free (temp_buf);
01703   return (0);
01704 }
01705 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:55