pcd_io.hpp
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: pcd_io.hpp 4968 2012-03-08 06:39:52Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_IO_PCD_IO_IMPL_H_
00041 #define PCL_IO_PCD_IO_IMPL_H_
00042 
00043 #include <fstream>
00044 #include <fcntl.h>
00045 #include <string>
00046 #include <stdlib.h>
00047 #include <boost/algorithm/string.hpp>
00048 #include <pcl/channel_properties.h>
00049 #include <pcl/console/print.h>
00050 #ifdef _WIN32
00051 # include <io.h>
00052 # ifndef WIN32_LEAN_AND_MEAN
00053 #  define WIN32_LEAN_AND_MEAN
00054 # endif WIN32_LEAN_AND_MEAN
00055 # ifndef NOMINMAX
00056 #  define NOMINMAX
00057 # endif NOMINMAX
00058 # include <windows.h>
00059 # define pcl_open                    _open
00060 # define pcl_close(fd)               _close(fd)
00061 # define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin)
00062 #else
00063 # include <sys/mman.h>
00064 # define pcl_open                    open
00065 # define pcl_close(fd)               close(fd)
00066 # define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin)
00067 #endif
00068 
00069 #include <pcl/io/lzf.h>
00070 
00072 template <typename PointT> std::string
00073 pcl::PCDWriter::generateHeader (const pcl::PointCloud<PointT> &cloud, const int nr_points)
00074 {
00075   std::ostringstream oss;
00076   oss.imbue (std::locale::classic ());
00077 
00078   oss << "# .PCD v0.7 - Point Cloud Data file format"
00079          "\nVERSION 0.7"
00080          "\nFIELDS";
00081 
00082   std::vector<sensor_msgs::PointField> fields;
00083   pcl::getFields (cloud, fields);
00084  
00085   std::stringstream field_names, field_types, field_sizes, field_counts;
00086   for (size_t i = 0; i < fields.size (); ++i)
00087   {
00088     if (fields[i].name == "_")
00089       continue;
00090     // Add the regular dimension
00091     field_names << " " << fields[i].name;
00092     field_sizes << " " << pcl::getFieldSize (fields[i].datatype);
00093     field_types << " " << pcl::getFieldType (fields[i].datatype);
00094     int count = abs (static_cast<int> (fields[i].count));
00095     if (count == 0) count = 1;  // check for 0 counts (coming from older converter code)
00096     field_counts << " " << count;
00097   }
00098   oss << field_names.str ();
00099   oss << "\nSIZE" << field_sizes.str () 
00100       << "\nTYPE" << field_types.str () 
00101       << "\nCOUNT" << field_counts.str ();
00102   // If the user passes in a number of points value, use that instead
00103   if (nr_points != std::numeric_limits<int>::max ())
00104     oss << "\nWIDTH " << nr_points << "\nHEIGHT " << 1 << "\n";
00105   else
00106     oss << "\nWIDTH " << cloud.width << "\nHEIGHT " << cloud.height << "\n";
00107 
00108   oss << "VIEWPOINT " << cloud.sensor_origin_[0] << " " << cloud.sensor_origin_[1] << " " << cloud.sensor_origin_[2] << " " << 
00109                          cloud.sensor_orientation_.w () << " " << 
00110                          cloud.sensor_orientation_.x () << " " << 
00111                          cloud.sensor_orientation_.y () << " " << 
00112                          cloud.sensor_orientation_.z () << "\n";
00113   
00114   // If the user passes in a number of points value, use that instead
00115   if (nr_points != std::numeric_limits<int>::max ())
00116     oss << "POINTS " << nr_points << "\n";
00117   else
00118     oss << "POINTS " << cloud.points.size () << "\n";
00119 
00120   return (oss.str ());
00121 }
00122 
00124 template <typename PointT> int
00125 pcl::PCDWriter::writeBinary (const std::string &file_name, 
00126                              const pcl::PointCloud<PointT> &cloud)
00127 {
00128   if (cloud.empty ())
00129   {
00130     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!");
00131     return (-1);
00132   }
00133   int data_idx = 0;
00134   std::ostringstream oss;
00135   oss << generateHeader<PointT> (cloud) << "DATA binary\n";
00136   oss.flush ();
00137   data_idx = static_cast<int> (oss.tellp ());
00138 
00139 #if _WIN32
00140   HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
00141   if(h_native_file == INVALID_HANDLE_VALUE)
00142   {
00143     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!");
00144     return (-1);
00145   }
00146 #else
00147   int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast<mode_t> (0600));
00148   if (fd < 0)
00149   {
00150     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!");
00151     return (-1);
00152   }
00153 #endif
00154 
00155   std::vector<sensor_msgs::PointField> fields;
00156   std::vector<int> fields_sizes;
00157   size_t fsize = 0;
00158   size_t data_size = 0;
00159   size_t nri = 0;
00160   pcl::getFields (cloud, fields);
00161   // Compute the total size of the fields
00162   for (size_t i = 0; i < fields.size (); ++i)
00163   {
00164     if (fields[i].name == "_")
00165       continue;
00166     
00167     int fs = fields[i].count * getFieldSize (fields[i].datatype);
00168     fsize += fs;
00169     fields_sizes.push_back (fs);
00170     fields[nri++] = fields[i];
00171   }
00172   fields.resize (nri);
00173   
00174   data_size = cloud.points.size () * fsize;
00175 
00176   // Prepare the map
00177 #if _WIN32
00178   HANDLE fm = CreateFileMappingA (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + data_size), NULL);
00179   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size));
00180   CloseHandle (fm);
00181 
00182 #else
00183   // Stretch the file size to the size of the data
00184   int result = static_cast<int> (pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET));
00185   if (result < 0)
00186   {
00187     pcl_close (fd);
00188     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during lseek ()!");
00189     return (-1);
00190   }
00191   // Write a bogus entry so that the new file size comes in effect
00192   result = static_cast<int> (::write (fd, "", 1));
00193   if (result != 1)
00194   {
00195     pcl_close (fd);
00196     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during write ()!");
00197     return (-1);
00198   }
00199 
00200   char *map = static_cast<char*> (mmap (0, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
00201   if (map == reinterpret_cast<char*> (-1)) //MAP_FAILED)
00202   {
00203     pcl_close (fd);
00204     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!");
00205     return (-1);
00206   }
00207 #endif
00208 
00209   // Copy the header
00210   memcpy (&map[0], oss.str ().c_str (), data_idx);
00211 
00212   // Copy the data
00213   char *out = &map[0] + data_idx;
00214   for (size_t i = 0; i < cloud.points.size (); ++i)
00215   {
00216     int nrj = 0;
00217     for (size_t j = 0; j < fields.size (); ++j)
00218     {
00219       memcpy (out, reinterpret_cast<const char*> (&cloud.points[i]) + fields[j].offset, fields_sizes[nrj]);
00220       out += fields_sizes[nrj++];
00221     }
00222   }
00223 
00224   // If the user set the synchronization flag on, call msync
00225 #if !_WIN32
00226   if (map_synchronization_)
00227     msync (map, data_idx + data_size, MS_SYNC);
00228 #endif
00229 
00230   // Unmap the pages of memory
00231 #if _WIN32
00232     UnmapViewOfFile (map);
00233 #else
00234   if (munmap (map, (data_idx + data_size)) == -1)
00235   {
00236     pcl_close (fd);
00237     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!");
00238     return (-1);
00239   }
00240 #endif
00241   // Close file
00242 #if _WIN32
00243   CloseHandle (h_native_file);
00244 #else
00245   pcl_close (fd);
00246 #endif
00247   return (0);
00248 }
00249 
00251 template <typename PointT> int
00252 pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, 
00253                                        const pcl::PointCloud<PointT> &cloud)
00254 {
00255   if (cloud.points.empty ())
00256   {
00257     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Input point cloud has no data!");
00258     return (-1);
00259   }
00260   int data_idx = 0;
00261   std::ostringstream oss;
00262   oss << generateHeader<PointT> (cloud) << "DATA binary_compressed\n";
00263   oss.flush ();
00264   data_idx = static_cast<int> (oss.tellp ());
00265 
00266 #if _WIN32
00267   HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
00268   if(h_native_file == INVALID_HANDLE_VALUE)
00269   {
00270     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during CreateFile!");
00271     return (-1);
00272   }
00273 #else
00274   int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast<mode_t> (0600));
00275   if (fd < 0)
00276   {
00277     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during open!");
00278     return (-1);
00279   }
00280 #endif
00281 
00282   std::vector<sensor_msgs::PointField> fields;
00283   size_t fsize = 0;
00284   size_t data_size = 0;
00285   size_t nri = 0;
00286   pcl::getFields (cloud, fields);
00287   std::vector<int> fields_sizes (fields.size ());
00288   // Compute the total size of the fields
00289   for (size_t i = 0; i < fields.size (); ++i)
00290   {
00291     if (fields[i].name == "_")
00292       continue;
00293     
00294     fields_sizes[nri] = fields[i].count * pcl::getFieldSize (fields[i].datatype);
00295     fsize += fields_sizes[nri];
00296     fields[nri] = fields[i];
00297     ++nri;
00298   }
00299   fields_sizes.resize (nri);
00300   fields.resize (nri);
00301  
00302   // Compute the size of data
00303   data_size = cloud.points.size () * fsize;
00304 
00306   // Empty array holding only the valid data
00307   // data_size = nr_points * point_size 
00308   //           = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n)
00309   //           = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ... sizeof_field_n * nr_points
00310   char *only_valid_data = static_cast<char*> (malloc (data_size));
00311 
00312   // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For
00313   // this, we need a vector of fields.size () (4 in this case), which points to
00314   // each individual plane:
00315   //   pters[0] = &only_valid_data[offset_of_plane_x];
00316   //   pters[1] = &only_valid_data[offset_of_plane_y];
00317   //   pters[2] = &only_valid_data[offset_of_plane_z];
00318   //   pters[3] = &only_valid_data[offset_of_plane_RGB];
00319   //
00320   std::vector<char*> pters (fields.size ());
00321   int toff = 0;
00322   for (size_t i = 0; i < pters.size (); ++i)
00323   {
00324     pters[i] = &only_valid_data[toff];
00325     toff += fields_sizes[i] * static_cast<int> (cloud.points.size ());
00326   }
00327   
00328   // Go over all the points, and copy the data in the appropriate places
00329   for (size_t i = 0; i < cloud.points.size (); ++i)
00330   {
00331     for (size_t j = 0; j < fields.size (); ++j)
00332     {
00333       memcpy (pters[j], reinterpret_cast<const char*> (&cloud.points[i]) + fields[j].offset, fields_sizes[j]);
00334       // Increment the pointer
00335       pters[j] += fields_sizes[j];
00336     }
00337   }
00338 
00339   char* temp_buf = static_cast<char*> (malloc (static_cast<size_t> (static_cast<float> (data_size) * 1.5f + 8.0f)));
00340   // Compress the valid data
00341   unsigned int compressed_size = pcl::lzfCompress (only_valid_data, 
00342                                                    static_cast<uint32_t> (data_size), 
00343                                                    &temp_buf[8], 
00344                                                    static_cast<uint32_t> (static_cast<float>(data_size) * 1.5f));
00345   unsigned int compressed_final_size = 0;
00346   // Was the compression successful?
00347   if (compressed_size)
00348   {
00349     char *header = &temp_buf[0];
00350     memcpy (&header[0], &compressed_size, sizeof (unsigned int));
00351     memcpy (&header[4], &data_size, sizeof (unsigned int));
00352     data_size = compressed_size + 8;
00353     compressed_final_size = static_cast<uint32_t> (data_size) + data_idx;
00354   }
00355   else
00356   {
00357 #if !_WIN32
00358     pcl_close (fd);
00359 #endif
00360     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during compression!");
00361     return (-1);
00362   }
00363 
00364 #if !_WIN32
00365   // Stretch the file size to the size of the data
00366   int result = static_cast<int> (pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET));
00367   if (result < 0)
00368   {
00369     pcl_close (fd);
00370     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during lseek ()!");
00371     return (-1);
00372   }
00373   // Write a bogus entry so that the new file size comes in effect
00374   result = static_cast<int> (::write (fd, "", 1));
00375   if (result != 1)
00376   {
00377     pcl_close (fd);
00378     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during write ()!");
00379     return (-1);
00380   }
00381 #endif
00382 
00383   // Prepare the map
00384 #if _WIN32
00385   HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, compressed_final_size, NULL);
00386   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, compressed_final_size));
00387   CloseHandle (fm);
00388 
00389 #else
00390   char *map = static_cast<char*> (mmap (0, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0));
00391   if (map == reinterpret_cast<char*> (-1)) //MAP_FAILED)
00392   {
00393     pcl_close (fd);
00394     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during mmap ()!");
00395     return (-1);
00396   }
00397 #endif
00398 
00399   // Copy the header
00400   memcpy (&map[0], oss.str ().c_str (), data_idx);
00401   // Copy the compressed data
00402   memcpy (&map[data_idx], temp_buf, data_size);
00403 
00404 #if !_WIN32
00405   // If the user set the synchronization flag on, call msync
00406   if (map_synchronization_)
00407     msync (map, compressed_final_size, MS_SYNC);
00408 #endif
00409 
00410   // Unmap the pages of memory
00411 #if _WIN32
00412     UnmapViewOfFile (map);
00413 #else
00414   if (munmap (map, (compressed_final_size)) == -1)
00415   {
00416     pcl_close (fd);
00417     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during munmap ()!");
00418     return (-1);
00419   }
00420 #endif
00421   // Close file
00422 #if _WIN32
00423   CloseHandle (h_native_file);
00424 #else
00425   pcl_close (fd);
00426 #endif
00427 
00428   free (only_valid_data);
00429   free (temp_buf);
00430   return (0);
00431 }
00432 
00434 template <typename PointT> int
00435 pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, 
00436                             const int precision)
00437 {
00438   if (cloud.empty ())
00439   {
00440     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Input point cloud has no data!");
00441     return (-1);
00442   }
00443 
00444   if (cloud.width * cloud.height != cloud.points.size ())
00445   {
00446     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!");
00447     return (-1);
00448   }
00449 
00450   std::ofstream fs;
00451   fs.open (file_name.c_str ());      // Open file
00452   
00453   if (!fs.is_open () || fs.fail ())
00454   {
00455     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!");
00456     return (-1);
00457   }
00458   
00459   fs.precision (precision);
00460   fs.imbue (std::locale::classic ());
00461 
00462   std::vector<sensor_msgs::PointField> fields;
00463   pcl::getFields (cloud, fields);
00464 
00465   // Write the header information
00466   fs << generateHeader<PointT> (cloud) << "DATA ascii\n";
00467 
00468   std::ostringstream stream;
00469   stream.precision (precision);
00470   stream.imbue (std::locale::classic ());
00471   // Iterate through the points
00472   for (size_t i = 0; i < cloud.points.size (); ++i)
00473   {
00474     for (size_t d = 0; d < fields.size (); ++d)
00475     {
00476       // Ignore invalid padded dimensions that are inherited from binary data
00477       if (fields[d].name == "_")
00478         continue;
00479 
00480       int count = fields[d].count;
00481       if (count == 0) 
00482         count = 1;          // we simply cannot tolerate 0 counts (coming from older converter code)
00483 
00484       for (int c = 0; c < count; ++c)
00485       {
00486         switch (fields[d].datatype)
00487         {
00488           case sensor_msgs::PointField::INT8:
00489           {
00490             int8_t value;
00491             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (int8_t), sizeof (int8_t));
00492             if (pcl_isnan (value))
00493               stream << "nan";
00494             else
00495               stream << boost::numeric_cast<uint32_t>(value);
00496             break;
00497           }
00498           case sensor_msgs::PointField::UINT8:
00499           {
00500             uint8_t value;
00501             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (uint8_t), sizeof (uint8_t));
00502             if (pcl_isnan (value))
00503               stream << "nan";
00504             else
00505               stream << boost::numeric_cast<uint32_t>(value);
00506             break;
00507           }
00508           case sensor_msgs::PointField::INT16:
00509           {
00510             int16_t value;
00511             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (int16_t), sizeof (int16_t));
00512             if (pcl_isnan (value))
00513               stream << "nan";
00514             else
00515               stream << boost::numeric_cast<int16_t>(value);
00516             break;
00517           }
00518           case sensor_msgs::PointField::UINT16:
00519           {
00520             uint16_t value;
00521             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (uint16_t), sizeof (uint16_t));
00522             if (pcl_isnan (value))
00523               stream << "nan";
00524             else
00525               stream << boost::numeric_cast<uint16_t>(value);
00526             break;
00527           }
00528           case sensor_msgs::PointField::INT32:
00529           {
00530             int32_t value;
00531             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (int32_t), sizeof (int32_t));
00532             if (pcl_isnan (value))
00533               stream << "nan";
00534             else
00535               stream << boost::numeric_cast<int32_t>(value);
00536             break;
00537           }
00538           case sensor_msgs::PointField::UINT32:
00539           {
00540             uint32_t value;
00541             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (uint32_t), sizeof (uint32_t));
00542             if (pcl_isnan (value))
00543               stream << "nan";
00544             else
00545               stream << boost::numeric_cast<uint32_t>(value);
00546             break;
00547           }
00548           case sensor_msgs::PointField::FLOAT32:
00549           {
00550             float value;
00551             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (float), sizeof (float));
00552             if (pcl_isnan (value))
00553               stream << "nan";
00554             else
00555               stream << boost::numeric_cast<float>(value);
00556             break;
00557           }
00558           case sensor_msgs::PointField::FLOAT64:
00559           {
00560             double value;
00561             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (double), sizeof (double));
00562             if (pcl_isnan (value))
00563               stream << "nan";
00564             else
00565               stream << boost::numeric_cast<double>(value);
00566             break;
00567           }
00568           default:
00569             PCL_WARN ("[pcl::PCDWriter::writeASCII] Incorrect field data type specified (%d)!\n", fields[d].datatype);
00570             break;
00571         }
00572 
00573         if (d < fields.size () - 1 || c < static_cast<int> (fields[d].count - 1))
00574           stream << " ";
00575       }
00576     }
00577     // Copy the stream, trim it, and write it to disk
00578     std::string result = stream.str ();
00579     boost::trim (result);
00580     stream.str ("");
00581     fs << result << "\n";
00582   }
00583   fs.close ();              // Close file
00584   return (0);
00585 }
00586 
00587 
00589 template <typename PointT> int
00590 pcl::PCDWriter::writeBinary (const std::string &file_name, 
00591                              const pcl::PointCloud<PointT> &cloud, 
00592                              const std::vector<int> &indices)
00593 {
00594   if (cloud.points.empty () || indices.empty ())
00595   {
00596     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Input point cloud has no data or empty indices given!");
00597     return (-1);
00598   }
00599   int data_idx = 0;
00600   std::ostringstream oss;
00601   oss << generateHeader<PointT> (cloud, static_cast<int> (indices.size ())) << "DATA binary\n";
00602   oss.flush ();
00603   data_idx = static_cast<int> (oss.tellp ());
00604 
00605 #if _WIN32
00606   HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
00607   if(h_native_file == INVALID_HANDLE_VALUE)
00608   {
00609     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!");
00610     return (-1);
00611   }
00612 #else
00613   int fd = pcl_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast<mode_t> (0600));
00614   if (fd < 0)
00615   {
00616     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!");
00617     return (-1);
00618   }
00619 #endif
00620 
00621   std::vector<sensor_msgs::PointField> fields;
00622   std::vector<int> fields_sizes;
00623   size_t fsize = 0;
00624   size_t data_size = 0;
00625   size_t nri = 0;
00626   pcl::getFields (cloud, fields);
00627   // Compute the total size of the fields
00628   for (size_t i = 0; i < fields.size (); ++i)
00629   {
00630     if (fields[i].name == "_")
00631       continue;
00632     
00633     int fs = fields[i].count * getFieldSize (fields[i].datatype);
00634     fsize += fs;
00635     fields_sizes.push_back (fs);
00636     fields[nri++] = fields[i];
00637   }
00638   fields.resize (nri);
00639   
00640   data_size = indices.size () * fsize;
00641 
00642   // Prepare the map
00643 #if _WIN32
00644   HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_idx + data_size, NULL);
00645   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size));
00646   CloseHandle (fm);
00647 
00648 #else
00649   // Stretch the file size to the size of the data
00650   int result = static_cast<int> (pcl_lseek (fd, getpagesize () + data_size - 1, SEEK_SET));
00651   if (result < 0)
00652   {
00653     pcl_close (fd);
00654     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during lseek ()!");
00655     return (-1);
00656   }
00657   // Write a bogus entry so that the new file size comes in effect
00658   result = static_cast<int> (::write (fd, "", 1));
00659   if (result != 1)
00660   {
00661     pcl_close (fd);
00662     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during write ()!");
00663     return (-1);
00664   }
00665 
00666   char *map = static_cast<char*> (mmap (0, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
00667   if (map == reinterpret_cast<char*> (-1)) //MAP_FAILED)
00668   {
00669     pcl_close (fd);
00670     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!");
00671     return (-1);
00672   }
00673 #endif
00674 
00675   // Copy the header
00676   memcpy (&map[0], oss.str ().c_str (), data_idx);
00677 
00678   char *out = &map[0] + data_idx;
00679   // Copy the data
00680   for (size_t i = 0; i < indices.size (); ++i)
00681   {
00682     int nrj = 0;
00683     for (size_t j = 0; j < fields.size (); ++j)
00684     {
00685       memcpy (out, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[j].offset, fields_sizes[nrj]);
00686       out += fields_sizes[nrj++];
00687     }
00688   }
00689 
00690 #if !_WIN32
00691   // If the user set the synchronization flag on, call msync
00692   if (map_synchronization_)
00693     msync (map, data_idx + data_size, MS_SYNC);
00694 #endif
00695 
00696   // Unmap the pages of memory
00697 #if _WIN32
00698     UnmapViewOfFile (map);
00699 #else
00700   if (munmap (map, (data_idx + data_size)) == -1)
00701   {
00702     pcl_close (fd);
00703     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!");
00704     return (-1);
00705   }
00706 #endif
00707   // Close file
00708 #if _WIN32
00709   CloseHandle(h_native_file);
00710 #else
00711   pcl_close (fd);
00712 #endif
00713   return (0);
00714 }
00715 
00717 template <typename PointT> int
00718 pcl::PCDWriter::writeASCII (const std::string &file_name, 
00719                             const pcl::PointCloud<PointT> &cloud, 
00720                             const std::vector<int> &indices,
00721                             const int precision)
00722 {
00723   if (cloud.points.empty () || indices.empty ())
00724   {
00725     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Input point cloud has no data or empty indices given!");
00726     return (-1);
00727   }
00728 
00729   if (cloud.width * cloud.height != cloud.points.size ())
00730   {
00731     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!");
00732     return (-1);
00733   }
00734 
00735   std::ofstream fs;
00736   fs.open (file_name.c_str ());      // Open file
00737   if (!fs.is_open () || fs.fail ())
00738   {
00739     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!");
00740     return (-1);
00741   }
00742   fs.precision (precision);
00743   fs.imbue (std::locale::classic ());
00744 
00745   std::vector<sensor_msgs::PointField> fields;
00746   pcl::getFields (cloud, fields);
00747 
00748   // Write the header information
00749   fs << generateHeader<PointT> (cloud, static_cast<int> (indices.size ())) << "DATA ascii\n";
00750 
00751   std::ostringstream stream;
00752   stream.precision (precision);
00753   stream.imbue (std::locale::classic ());
00754 
00755   // Iterate through the points
00756   for (size_t i = 0; i < indices.size (); ++i)
00757   {
00758     for (size_t d = 0; d < fields.size (); ++d)
00759     {
00760       // Ignore invalid padded dimensions that are inherited from binary data
00761       if (fields[d].name == "_")
00762         continue;
00763 
00764       int count = fields[d].count;
00765       if (count == 0) 
00766         count = 1;          // we simply cannot tolerate 0 counts (coming from older converter code)
00767 
00768       for (int c = 0; c < count; ++c)
00769       {
00770         switch (fields[d].datatype)
00771         {
00772           case sensor_msgs::PointField::INT8:
00773           {
00774             int8_t value;
00775             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (int8_t), sizeof (int8_t));
00776             if (pcl_isnan (value))
00777               stream << "nan";
00778             else
00779               stream << boost::numeric_cast<uint32_t>(value);
00780             break;
00781           }
00782           case sensor_msgs::PointField::UINT8:
00783           {
00784             uint8_t value;
00785             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (uint8_t), sizeof (uint8_t));
00786             if (pcl_isnan (value))
00787               stream << "nan";
00788             else
00789               stream << boost::numeric_cast<uint32_t>(value);
00790             break;
00791           }
00792           case sensor_msgs::PointField::INT16:
00793           {
00794             int16_t value;
00795             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (int16_t), sizeof (int16_t));
00796             if (pcl_isnan (value))
00797               stream << "nan";
00798             else
00799               stream << boost::numeric_cast<int16_t>(value);
00800             break;
00801           }
00802           case sensor_msgs::PointField::UINT16:
00803           {
00804             uint16_t value;
00805             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (uint16_t), sizeof (uint16_t));
00806             if (pcl_isnan (value))
00807               stream << "nan";
00808             else
00809               stream << boost::numeric_cast<uint16_t>(value);
00810             break;
00811           }
00812           case sensor_msgs::PointField::INT32:
00813           {
00814             int32_t value;
00815             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (int32_t), sizeof (int32_t));
00816             if (pcl_isnan (value))
00817               stream << "nan";
00818             else
00819               stream << boost::numeric_cast<int32_t>(value);
00820             break;
00821           }
00822           case sensor_msgs::PointField::UINT32:
00823           {
00824             uint32_t value;
00825             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (uint32_t), sizeof (uint32_t));
00826             if (pcl_isnan (value))
00827               stream << "nan";
00828             else
00829               stream << boost::numeric_cast<uint32_t>(value);
00830             break;
00831           }
00832           case sensor_msgs::PointField::FLOAT32:
00833           {
00834             float value;
00835             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (float), sizeof (float));
00836             if (pcl_isnan (value))
00837               stream << "nan";
00838             else
00839               stream << boost::numeric_cast<float>(value);
00840             break;
00841           }
00842           case sensor_msgs::PointField::FLOAT64:
00843           {
00844             double value;
00845             memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (double), sizeof (double));
00846             if (pcl_isnan (value))
00847               stream << "nan";
00848             else
00849               stream << boost::numeric_cast<double>(value);
00850             break;
00851           }
00852           default:
00853             PCL_WARN ("[pcl::PCDWriter::writeASCII] Incorrect field data type specified (%d)!\n", fields[d].datatype);
00854             break;
00855         }
00856 
00857         if (d < fields.size () - 1 || c < static_cast<int> (fields[d].count - 1))
00858           stream << " ";
00859       }
00860     }
00861     // Copy the stream, trim it, and write it to disk
00862     std::string result = stream.str ();
00863     boost::trim (result);
00864     stream.str ("");
00865     fs << result << "\n";
00866   }
00867   fs.close ();              // Close file
00868   return (0);
00869 }
00870 
00871 #endif  //#ifndef PCL_IO_PCD_IO_H_
00872 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:24