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  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #include <pcl/point_types.h>
00042 #include <pcl/common/io.h>
00043 
00045 void
00046 getFieldsSizes (const std::vector<pcl::PCLPointField> &fields,
00047                 std::vector<int> &fields_sizes)
00048 {
00049   int valid = 0;
00050   fields_sizes.resize (fields.size ());
00051   for (size_t i = 0; i < fields.size (); ++i)
00052   {
00053     if (fields[i].name == "_")
00054       continue;
00055 
00056     int fs = fields[i].count * pcl::getFieldSize (fields[i].datatype);
00057     fields_sizes[i] = fs;
00058     valid++;
00059   }
00060   fields_sizes.resize (valid);
00061 }
00062 
00063 bool fieldComp (const pcl::PCLPointField* i, const pcl::PCLPointField* j)
00064 {
00065   return i->offset < j->offset;
00066 }
00067 
00069 bool
00070 pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
00071                         const pcl::PCLPointCloud2 &cloud2,
00072                         pcl::PCLPointCloud2 &cloud_out)
00073 {
00074   // If the cloud's sizes differ (points wise), then exit with error
00075   if (cloud1.width != cloud2.width || cloud1.height != cloud2.height)
00076   {
00077     PCL_ERROR ("[pcl::concatenateFields] Dimensions of input clouds do not match: cloud1 (w, %d, h, %d), cloud2 (w, %d, h, %d)\n", cloud1.width, cloud1.height, cloud2.width, cloud2.height );
00078     return (false);
00079   }
00080   
00081 
00082   if (cloud1.is_bigendian != cloud2.is_bigendian)
00083   {
00084     PCL_ERROR ("[pcl::concatenateFields] Endianness of clouds does not match\n");
00085     return (false);
00086   }
00087   
00088   // Else, copy the second cloud (width, height, header stay the same)
00089   // we do this since fields from the second cloud are supposed to overwrite
00090   // those of the first
00091   cloud_out.header = cloud2.header;
00092   cloud_out.fields = cloud2.fields;
00093   cloud_out.width = cloud2.width;
00094   cloud_out.height = cloud2.height;
00095   cloud_out.is_bigendian = cloud2.is_bigendian;
00096 
00097   //We need to find how many fields overlap between the two clouds
00098   size_t total_fields = cloud2.fields.size ();
00099 
00100   //for the non-matching fields in cloud1, we need to store the offset
00101   //from the beginning of the point
00102   std::vector<const pcl::PCLPointField*> cloud1_unique_fields;
00103   std::vector<int> field_sizes;
00104 
00105   //We need to make sure that the fields for cloud 1 are sorted
00106   //by offset so that we can compute sizes correctly. There is no
00107   //guarantee that the fields are in the correct order when they come in
00108   std::vector<const pcl::PCLPointField*> cloud1_fields_sorted;
00109   for (size_t i = 0; i < cloud1.fields.size (); ++i)
00110     cloud1_fields_sorted.push_back (&(cloud1.fields[i]));
00111 
00112   std::sort (cloud1_fields_sorted.begin (), cloud1_fields_sorted.end (), fieldComp);
00113 
00114   for (size_t i = 0; i < cloud1_fields_sorted.size (); ++i)
00115   {
00116     bool match = false;
00117     for (size_t j = 0; j < cloud2.fields.size (); ++j)
00118     {
00119       if (cloud1_fields_sorted[i]->name == cloud2.fields[j].name)
00120         match = true;
00121     }
00122 
00123     //if the field is new, we'll increment out total fields
00124     if (!match && cloud1_fields_sorted[i]->name != "_")
00125     {
00126       cloud1_unique_fields.push_back (cloud1_fields_sorted[i]);
00127 
00128       int size = 0;
00129       size_t next_valid_field = i + 1;
00130 
00131       while (next_valid_field < cloud1_fields_sorted.size())
00132       {
00133         if (cloud1_fields_sorted[next_valid_field]->name != "_")
00134           break;
00135         next_valid_field++;
00136       }
00137 
00138       if (next_valid_field < cloud1_fields_sorted.size ())
00139         //compute the true size of the field, including padding
00140         size = cloud1_fields_sorted[next_valid_field]->offset - cloud1_fields_sorted[i]->offset;
00141       else
00142         //for the last point, we'll just use the point step to compute the size
00143         size = cloud1.point_step - cloud1_fields_sorted[i]->offset;
00144 
00145       field_sizes.push_back (size);
00146 
00147       total_fields++;
00148     }
00149   }
00150 
00151   //we need to compute the size of the additional data added from cloud 1
00152   uint32_t cloud1_unique_point_step = 0;
00153   for (size_t i = 0; i < cloud1_unique_fields.size (); ++i)
00154     cloud1_unique_point_step += field_sizes[i];
00155 
00156   //the total size of extra data should be the size of data per point
00157   //multiplied by the total number of points in the cloud
00158   uint32_t cloud1_unique_data_size = cloud1_unique_point_step * cloud1.width * cloud1.height; 
00159 
00160   // Point step must increase with the length of each matching field
00161   cloud_out.point_step = cloud2.point_step + cloud1_unique_point_step;
00162   // Recalculate row_step
00163   cloud_out.row_step = cloud_out.point_step * cloud_out.width;
00164 
00165   // Resize data to hold all clouds
00166   cloud_out.data.resize (cloud2.data.size () + cloud1_unique_data_size);
00167 
00168   // Concatenate fields
00169   cloud_out.fields.resize (cloud2.fields.size () + cloud1_unique_fields.size ());
00170   int offset = cloud2.point_step;
00171 
00172   for (size_t d = 0; d < cloud1_unique_fields.size (); ++d)
00173   {
00174     const pcl::PCLPointField& f = *cloud1_unique_fields[d];
00175     cloud_out.fields[cloud2.fields.size () + d].name = f.name;
00176     cloud_out.fields[cloud2.fields.size () + d].datatype = f.datatype;
00177     cloud_out.fields[cloud2.fields.size () + d].count = f.count;
00178     // Adjust the offset
00179     cloud_out.fields[cloud2.fields.size () + d].offset = offset;
00180     offset += field_sizes[d];
00181   }
00182  
00183   // Iterate over each point and perform the appropriate memcpys
00184   int point_offset = 0;
00185   for (size_t cp = 0; cp < cloud_out.width * cloud_out.height; ++cp)
00186   {
00187     memcpy (&cloud_out.data[point_offset], &cloud2.data[cp * cloud2.point_step], cloud2.point_step);
00188     int field_offset = cloud2.point_step;
00189 
00190     // Copy each individual point, we have to do this on a per-field basis
00191     // since some fields are not unique
00192     for (size_t i = 0; i < cloud1_unique_fields.size (); ++i)
00193     {
00194       const pcl::PCLPointField& f = *cloud1_unique_fields[i];
00195       int local_data_size = f.count * pcl::getFieldSize (f.datatype);
00196       int padding_size = field_sizes[i] - local_data_size;
00197       
00198       memcpy (&cloud_out.data[point_offset + field_offset], &cloud1.data[cp * cloud1.point_step + f.offset], local_data_size);
00199       field_offset +=  local_data_size;
00200 
00201       //make sure that we add padding when its needed
00202       if (padding_size > 0)
00203         memset (&cloud_out.data[point_offset + field_offset], 0, padding_size);
00204       field_offset += padding_size;
00205     }
00206     point_offset += field_offset;
00207   }
00208 
00209   if (!cloud1.is_dense || !cloud2.is_dense)
00210     cloud_out.is_dense = false;
00211   else
00212     cloud_out.is_dense = true;
00213 
00214   return (true);
00215 }
00216 
00218 bool
00219 pcl::concatenatePointCloud (const pcl::PCLPointCloud2 &cloud1,
00220                             const pcl::PCLPointCloud2 &cloud2,
00221                             pcl::PCLPointCloud2 &cloud_out)
00222 {
00223   //if one input cloud has no points, but the other input does, just return the cloud with points
00224   if (cloud1.width*cloud1.height == 0 && cloud2.width*cloud2.height > 0)
00225   {
00226     cloud_out = cloud2;
00227     return (true);
00228   }
00229   else if (cloud1.width*cloud1.height > 0 && cloud2.width*cloud2.height == 0)
00230   {
00231     cloud_out = cloud1;
00232     return (true);
00233   }
00234 
00235   bool strip = false;
00236   for (size_t i = 0; i < cloud1.fields.size (); ++i)
00237     if (cloud1.fields[i].name == "_")
00238       strip = true;
00239 
00240   for (size_t i = 0; i < cloud2.fields.size (); ++i)
00241     if (cloud2.fields[i].name == "_")
00242       strip = true;
00243 
00244   if (!strip && cloud1.fields.size () != cloud2.fields.size ())
00245   {
00246     PCL_ERROR ("[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.fields.size (), cloud2.fields.size ());
00247     return (false);
00248   }
00249   
00250   // Copy cloud1 into cloud_out
00251   cloud_out = cloud1;
00252   size_t nrpts = cloud_out.data.size ();
00253   // Height = 1 => no more organized
00254   cloud_out.width    = cloud1.width * cloud1.height + cloud2.width * cloud2.height;
00255   cloud_out.height   = 1;
00256   if (!cloud1.is_dense || !cloud2.is_dense)
00257     cloud_out.is_dense = false;
00258   else
00259     cloud_out.is_dense = true;
00260 
00261   // We need to strip the extra padding fields
00262   if (strip)
00263   {
00264     // Get the field sizes for the second cloud
00265     std::vector<pcl::PCLPointField> fields2;
00266     std::vector<int> fields2_sizes;
00267     for (size_t j = 0; j < cloud2.fields.size (); ++j)
00268     {
00269       if (cloud2.fields[j].name == "_")
00270         continue;
00271 
00272       fields2_sizes.push_back (cloud2.fields[j].count * 
00273                                pcl::getFieldSize (cloud2.fields[j].datatype));
00274       fields2.push_back (cloud2.fields[j]);
00275     }
00276 
00277     cloud_out.data.resize (nrpts + (cloud2.width * cloud2.height) * cloud_out.point_step);
00278 
00279     // Copy the second cloud
00280     for (size_t cp = 0; cp < cloud2.width * cloud2.height; ++cp)
00281     {
00282       int i = 0;
00283       for (size_t j = 0; j < fields2.size (); ++j)
00284       {
00285         if (cloud1.fields[i].name == "_")
00286         {
00287           ++i;
00288           continue;
00289         }
00290 
00291         // We're fine with the special RGB vs RGBA use case
00292         if ((cloud1.fields[i].name == "rgb" && fields2[j].name == "rgba") ||
00293             (cloud1.fields[i].name == "rgba" && fields2[j].name == "rgb") ||
00294             (cloud1.fields[i].name == fields2[j].name))
00295         {
00296           memcpy (reinterpret_cast<char*> (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]), 
00297                   reinterpret_cast<const char*> (&cloud2.data[cp * cloud2.point_step + cloud2.fields[j].offset]), 
00298                   fields2_sizes[j]);
00299           ++i;  // increment the field size i
00300         }
00301       }
00302     }
00303   }
00304   else
00305   {
00306     for (size_t i = 0; i < cloud1.fields.size (); ++i)
00307     {
00308       // We're fine with the special RGB vs RGBA use case
00309       if ((cloud1.fields[i].name == "rgb" && cloud2.fields[i].name == "rgba") ||
00310           (cloud1.fields[i].name == "rgba" && cloud2.fields[i].name == "rgb"))
00311         continue;
00312       // Otherwise we need to make sure the names are the same
00313       if (cloud1.fields[i].name != cloud2.fields[i].name)
00314       {
00315         PCL_ERROR ("[pcl::concatenatePointCloud] Name of field %d in cloud1, %s, does not match name in cloud2, %s\n", i, cloud1.fields[i].name.c_str (), cloud2.fields[i].name.c_str ());      
00316         return (false);
00317       }
00318     }
00319     
00320     cloud_out.data.resize (nrpts + cloud2.data.size ());
00321     memcpy (&cloud_out.data[nrpts], &cloud2.data[0], cloud2.data.size ());
00322   }
00323   return (true);
00324 }
00325 
00327 bool
00328 pcl::getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out)
00329 {
00330   // Get X-Y-Z indices
00331   int x_idx = getFieldIndex (in, "x");
00332   int y_idx = getFieldIndex (in, "y");
00333   int z_idx = getFieldIndex (in, "z");
00334 
00335   if (x_idx == -1 || y_idx == -1 || z_idx == -1)
00336   {
00337     PCL_ERROR ("Input dataset has no X-Y-Z coordinates! Cannot convert to Eigen format.\n");
00338     return (false);
00339   }
00340 
00341   if (in.fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 ||
00342       in.fields[y_idx].datatype != pcl::PCLPointField::FLOAT32 ||
00343       in.fields[z_idx].datatype != pcl::PCLPointField::FLOAT32)
00344   {
00345     PCL_ERROR ("X-Y-Z coordinates not floats. Currently only floats are supported.\n");
00346     return (false);
00347   }
00348 
00349   size_t npts = in.width * in.height;
00350   out = Eigen::MatrixXf::Ones (4, npts);
00351 
00352   Eigen::Array4i xyz_offset (in.fields[x_idx].offset, in.fields[y_idx].offset, in.fields[z_idx].offset, 0);
00353 
00354   // Copy the input dataset into Eigen format
00355   for (size_t i = 0; i < npts; ++i)
00356   {
00357      // Unoptimized memcpys: assume fields x, y, z are in random order
00358      memcpy (&out (0, i), &in.data[xyz_offset[0]], sizeof (float));
00359      memcpy (&out (1, i), &in.data[xyz_offset[1]], sizeof (float));
00360      memcpy (&out (2, i), &in.data[xyz_offset[2]], sizeof (float));
00361 
00362      xyz_offset += in.point_step;
00363   }
00364 
00365   return (true);
00366 }
00367 
00369 bool 
00370 pcl::getEigenAsPointCloud (Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out)
00371 {
00372   // Get X-Y-Z indices
00373   int x_idx = getFieldIndex (out, "x");
00374   int y_idx = getFieldIndex (out, "y");
00375   int z_idx = getFieldIndex (out, "z");
00376 
00377   if (x_idx == -1 || y_idx == -1 || z_idx == -1)
00378   {
00379     PCL_ERROR ("Output dataset has no X-Y-Z coordinates set up as fields! Cannot convert from Eigen format.\n");
00380     return (false);
00381   }
00382 
00383   if (out.fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 ||
00384       out.fields[y_idx].datatype != pcl::PCLPointField::FLOAT32 ||
00385       out.fields[z_idx].datatype != pcl::PCLPointField::FLOAT32)
00386   {
00387     PCL_ERROR ("X-Y-Z coordinates not floats. Currently only floats are supported.\n");
00388     return (false);
00389   }
00390 
00391   if (in.cols () != static_cast<int>(out.width * out.height))
00392   {
00393     PCL_ERROR ("Number of points in the point cloud differs from the Eigen matrix. Cannot continue.\n");
00394     return (false);
00395   }
00396 
00397   size_t npts = in.cols ();
00398 
00399   Eigen::Array4i xyz_offset (out.fields[x_idx].offset, out.fields[y_idx].offset, out.fields[z_idx].offset, 0);
00400 
00401   // Copy the input dataset into Eigen format
00402   for (size_t i = 0; i < npts; ++i)
00403   {
00404      // Unoptimized memcpys: assume fields x, y, z are in random order
00405      memcpy (&out.data[xyz_offset[0]], &in (0, i), sizeof (float));
00406      memcpy (&out.data[xyz_offset[1]], &in (1, i), sizeof (float));
00407      memcpy (&out.data[xyz_offset[2]], &in (2, i), sizeof (float));
00408 
00409      xyz_offset += out.point_step;
00410   }
00411 
00412   return (true);
00413 }
00414 
00416 void 
00417 pcl::copyPointCloud (
00418     const pcl::PCLPointCloud2 &cloud_in,
00419     const std::vector<int> &indices, 
00420     pcl::PCLPointCloud2 &cloud_out)
00421 {
00422   cloud_out.header       = cloud_in.header;
00423   cloud_out.height       = 1;
00424   cloud_out.width        = static_cast<uint32_t> (indices.size ()); 
00425   cloud_out.fields       = cloud_in.fields;
00426   cloud_out.is_bigendian = cloud_in.is_bigendian;
00427   cloud_out.point_step   = cloud_in.point_step;
00428   cloud_out.row_step     = cloud_in.row_step;
00429   cloud_out.is_dense     = cloud_in.is_dense;
00430 
00431   cloud_out.data.resize (cloud_out.width * cloud_out.height * cloud_out.point_step);
00432 
00433   // Iterate over each point
00434   for (size_t i = 0; i < indices.size (); ++i)
00435     memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[indices[i] * cloud_in.point_step], cloud_in.point_step);
00436 }
00437 
00439 void 
00440 pcl::copyPointCloud (
00441     const pcl::PCLPointCloud2 &cloud_in,
00442     const std::vector<int, Eigen::aligned_allocator<int> > &indices, 
00443     pcl::PCLPointCloud2 &cloud_out)
00444 {
00445   cloud_out.header       = cloud_in.header;
00446   cloud_out.height       = 1;
00447   cloud_out.width        = static_cast<uint32_t> (indices.size ()); 
00448   cloud_out.fields       = cloud_in.fields;
00449   cloud_out.is_bigendian = cloud_in.is_bigendian;
00450   cloud_out.point_step   = cloud_in.point_step;
00451   cloud_out.row_step     = cloud_in.row_step;
00452   cloud_out.is_dense     = cloud_in.is_dense;
00453 
00454   cloud_out.data.resize (cloud_out.width * cloud_out.height * cloud_out.point_step);
00455 
00456   // Iterate over each point
00457   for (size_t i = 0; i < indices.size (); ++i)
00458     memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[indices[i] * cloud_in.point_step], cloud_in.point_step);
00459 }
00460 
00462 void 
00463 pcl::copyPointCloud (const pcl::PCLPointCloud2 &cloud_in,
00464                      pcl::PCLPointCloud2 &cloud_out)
00465 {
00466   cloud_out.header       = cloud_in.header;
00467   cloud_out.height       = cloud_in.height;
00468   cloud_out.width        = cloud_in.width;
00469   cloud_out.fields       = cloud_in.fields;
00470   cloud_out.is_bigendian = cloud_in.is_bigendian;
00471   cloud_out.point_step   = cloud_in.point_step;
00472   cloud_out.row_step     = cloud_in.row_step;
00473   cloud_out.is_dense     = cloud_in.is_dense;
00474   cloud_out.data         = cloud_in.data;
00475 }
00476 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:02