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: io.hpp 6126 2012-07-03 20:19:58Z aichim $
00037  *
00038  */
00039 
00040 #ifndef PCL_IO_IMPL_IO_HPP_
00041 #define PCL_IO_IMPL_IO_HPP_
00042 
00043 #include <pcl/common/concatenate.h>
00044 
00046 template <typename PointT> int
00047 pcl::getFieldIndex (const pcl::PointCloud<PointT> &, 
00048                     const std::string &field_name, 
00049                     std::vector<sensor_msgs::PointField> &fields)
00050 {
00051   fields.clear ();
00052   // Get the fields list
00053   pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00054   for (size_t d = 0; d < fields.size (); ++d)
00055     if (fields[d].name == field_name)
00056       return (static_cast<int>(d));
00057   return (-1);
00058 }
00059 
00061 template <typename PointT> int
00062 pcl::getFieldIndex (const std::string &field_name, 
00063                     std::vector<sensor_msgs::PointField> &fields)
00064 {
00065   fields.clear ();
00066   // Get the fields list
00067   pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00068   for (size_t d = 0; d < fields.size (); ++d)
00069     if (fields[d].name == field_name)
00070       return (static_cast<int>(d));
00071   return (-1);
00072 }
00073 
00075 template <typename PointT> void
00076 pcl::getFields (const pcl::PointCloud<PointT> &, std::vector<sensor_msgs::PointField> &fields)
00077 {
00078   fields.clear ();
00079   // Get the fields list
00080   pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00081 }
00082 
00084 template <typename PointT> void
00085 pcl::getFields (std::vector<sensor_msgs::PointField> &fields)
00086 {
00087   fields.clear ();
00088   // Get the fields list
00089   pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00090 }
00091 
00093 template <typename PointT> std::string
00094 pcl::getFieldsList (const pcl::PointCloud<PointT> &)
00095 {
00096   // Get the fields list
00097   std::vector<sensor_msgs::PointField> fields;
00098   pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00099   std::string result;
00100   for (size_t i = 0; i < fields.size () - 1; ++i)
00101     result += fields[i].name + " ";
00102   result += fields[fields.size () - 1].name;
00103   return (result);
00104 }
00105 
00107 template <typename PointInT, typename PointOutT> void
00108 pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, pcl::PointCloud<PointOutT> &cloud_out)
00109 {
00110   // Allocate enough space and copy the basics
00111   cloud_out.points.resize (cloud_in.points.size ());
00112   cloud_out.header   = cloud_in.header;
00113   cloud_out.width    = cloud_in.width;
00114   cloud_out.height   = cloud_in.height;
00115   cloud_out.is_dense = cloud_in.is_dense;
00116   // Copy all the data fields from the input cloud to the output one
00117   typedef typename pcl::traits::fieldList<PointInT>::type FieldListInT;
00118   typedef typename pcl::traits::fieldList<PointOutT>::type FieldListOutT;
00119   typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList; 
00120   // Iterate over each point
00121   for (size_t i = 0; i < cloud_in.points.size (); ++i)
00122   {
00123     // Iterate over each dimension
00124     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (cloud_in.points[i], cloud_out.points[i]));
00125   }
00126 }
00127 
00129 template <typename PointT> void
00130 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, const std::vector<int> &indices,
00131                      pcl::PointCloud<PointT> &cloud_out)
00132 {
00133   // Allocate enough space and copy the basics
00134   cloud_out.points.resize (indices.size ());
00135   cloud_out.header   = cloud_in.header;
00136   cloud_out.width    = static_cast<uint32_t>(indices.size ());
00137   cloud_out.height   = 1;
00138   if (cloud_in.is_dense)
00139     cloud_out.is_dense = true;
00140   else
00141     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00142     // To verify this, we would need to iterate over all points and check for NaNs
00143     cloud_out.is_dense = false;
00144 
00145   // Copy all the data fields from the input cloud to the output one
00146   typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00147   // Iterate over each point
00148   for (size_t i = 0; i < indices.size (); ++i)
00149     // Iterate over each dimension
00150     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices[i]], cloud_out.points[i]));
00151 }
00152 
00154 template <typename PointT> void
00155 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00156                      const std::vector<int, Eigen::aligned_allocator<int> > &indices,
00157                      pcl::PointCloud<PointT> &cloud_out)
00158 {
00159   // Allocate enough space and copy the basics
00160   cloud_out.points.resize (indices.size ());
00161   cloud_out.header   = cloud_in.header;
00162   cloud_out.width    = static_cast<uint32_t> (indices.size ());
00163   cloud_out.height   = 1;
00164   if (cloud_in.is_dense)
00165     cloud_out.is_dense = true;
00166   else
00167     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00168     // To verify this, we would need to iterate over all points and check for NaNs
00169     cloud_out.is_dense = false;
00170 
00171   // Copy all the data fields from the input cloud to the output one
00172   typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00173   // Iterate over each point
00174   for (size_t i = 0; i < indices.size (); ++i)
00175     // Iterate over each dimension
00176     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices[i]], cloud_out.points[i]));
00177 }
00178 
00180 template <typename PointInT, typename PointOutT> void
00181 pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, const std::vector<int> &indices,
00182                      pcl::PointCloud<PointOutT> &cloud_out)
00183 {
00184   // Allocate enough space and copy the basics
00185   cloud_out.points.resize (indices.size ());
00186   cloud_out.header   = cloud_in.header;
00187   cloud_out.width    = indices.size ();
00188   cloud_out.height   = 1;
00189   if (cloud_in.is_dense)
00190     cloud_out.is_dense = true;
00191   else
00192     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00193     // To verify this, we would need to iterate over all points and check for NaNs
00194     cloud_out.is_dense = false;
00195 
00196   // Copy all the data fields from the input cloud to the output one
00197   typedef typename pcl::traits::fieldList<PointInT>::type FieldListInT;
00198   typedef typename pcl::traits::fieldList<PointOutT>::type FieldListOutT;
00199   typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList; 
00200   // Iterate over each point
00201   for (size_t i = 0; i < indices.size (); ++i)
00202     // Iterate over each dimension
00203     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (cloud_in.points[indices[i]], cloud_out.points[i]));
00204 }
00205 
00207 template <typename PointInT, typename PointOutT> void
00208 pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, 
00209                      const std::vector<int, Eigen::aligned_allocator<int> > &indices,
00210                      pcl::PointCloud<PointOutT> &cloud_out)
00211 {
00212   // Allocate enough space and copy the basics
00213   cloud_out.points.resize (indices.size ());
00214   cloud_out.header   = cloud_in.header;
00215   cloud_out.width    = static_cast<uint32_t> (indices.size ());
00216   cloud_out.height   = 1;
00217   if (cloud_in.is_dense)
00218     cloud_out.is_dense = true;
00219   else
00220     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00221     // To verify this, we would need to iterate over all points and check for NaNs
00222     cloud_out.is_dense = false;
00223 
00224   // Copy all the data fields from the input cloud to the output one
00225   typedef typename pcl::traits::fieldList<PointInT>::type FieldListInT;
00226   typedef typename pcl::traits::fieldList<PointOutT>::type FieldListOutT;
00227   typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList; 
00228   // Iterate over each point
00229   for (size_t i = 0; i < indices.size (); ++i)
00230     // Iterate over each dimension
00231     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (cloud_in.points[indices[i]], cloud_out.points[i]));
00232 }
00233 
00235 template <typename PointT> void
00236 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, const pcl::PointIndices &indices,
00237                      pcl::PointCloud<PointT> &cloud_out)
00238 {
00239   // Allocate enough space and copy the basics
00240   cloud_out.points.resize (indices.indices.size ());
00241   cloud_out.header   = cloud_in.header;
00242   cloud_out.width    = indices.indices.size ();
00243   cloud_out.height   = 1;
00244   if (cloud_in.is_dense)
00245     cloud_out.is_dense = true;
00246   else
00247     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00248     // To verify this, we would need to iterate over all points and check for NaNs
00249     cloud_out.is_dense = false;
00250 
00251   // Copy all the data fields from the input cloud to the output one
00252   typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00253   // Iterate over each point
00254   for (size_t i = 0; i < indices.indices.size (); ++i)
00255     // Iterate over each dimension
00256     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices.indices[i]], cloud_out.points[i]));
00257 }
00258 
00260 template <typename PointInT, typename PointOutT> void
00261 pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, const pcl::PointIndices &indices,
00262                      pcl::PointCloud<PointOutT> &cloud_out)
00263 {
00264   // Allocate enough space and copy the basics
00265   cloud_out.points.resize (indices.indices.size ());
00266   cloud_out.header   = cloud_in.header;
00267   cloud_out.width    = indices.indices.size ();
00268   cloud_out.height   = 1;
00269   if (cloud_in.is_dense)
00270     cloud_out.is_dense = true;
00271   else
00272     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00273     // To verify this, we would need to iterate over all points and check for NaNs
00274     cloud_out.is_dense = false;
00275 
00276   // Copy all the data fields from the input cloud to the output one
00277   typedef typename pcl::traits::fieldList<PointInT>::type FieldListInT;
00278   typedef typename pcl::traits::fieldList<PointOutT>::type FieldListOutT;
00279   typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList; 
00280   // Iterate over each point
00281   for (size_t i = 0; i < indices.indices.size (); ++i)
00282     // Iterate over each dimension
00283     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (cloud_in.points[indices.indices[i]], cloud_out.points[i]));
00284 }
00285 
00287 template <typename PointT> void
00288 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, const std::vector<pcl::PointIndices> &indices,
00289                      pcl::PointCloud<PointT> &cloud_out)
00290 {
00291   int nr_p = 0;
00292   for (size_t i = 0; i < indices.size (); ++i)
00293     nr_p += indices[i].indices.size ();
00294 
00295   // Allocate enough space and copy the basics
00296   cloud_out.points.resize (nr_p);
00297   cloud_out.header   = cloud_in.header;
00298   cloud_out.width    = nr_p;
00299   cloud_out.height   = 1;
00300   if (cloud_in.is_dense)
00301     cloud_out.is_dense = true;
00302   else
00303     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00304     // To verify this, we would need to iterate over all points and check for NaNs
00305     cloud_out.is_dense = false;
00306 
00307   // Copy all the data fields from the input cloud to the output one
00308   typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00309   // Iterate over each cluster
00310   int cp = 0;
00311   for (size_t cc = 0; cc < indices.size (); ++cc)
00312   {
00313     // Iterate over each idx
00314     for (size_t i = 0; i < indices[cc].indices.size (); ++i)
00315     {
00316       // Iterate over each dimension
00317       pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices[cc].indices[i]], cloud_out.points[cp]));
00318       cp++;
00319     }
00320   }
00321 }
00322 
00324 template <typename PointInT, typename PointOutT> void
00325 pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, const std::vector<pcl::PointIndices> &indices,
00326                      pcl::PointCloud<PointOutT> &cloud_out)
00327 {
00328   int nr_p = 0;
00329   for (size_t i = 0; i < indices.size (); ++i)
00330     nr_p += indices[i].indices.size ();
00331 
00332   // Allocate enough space and copy the basics
00333   cloud_out.points.resize (nr_p);
00334   cloud_out.header   = cloud_in.header;
00335   cloud_out.width    = nr_p;
00336   cloud_out.height   = 1;
00337   if (cloud_in.is_dense)
00338     cloud_out.is_dense = true;
00339   else
00340     // It's not necessarily true that is_dense is false if cloud_in.is_dense is false
00341     // To verify this, we would need to iterate over all points and check for NaNs
00342     cloud_out.is_dense = false;
00343 
00344   // Copy all the data fields from the input cloud to the output one
00345   typedef typename pcl::traits::fieldList<PointInT>::type FieldListInT;
00346   typedef typename pcl::traits::fieldList<PointOutT>::type FieldListOutT;
00347   typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList; 
00348   // Iterate over each cluster
00349   int cp = 0;
00350   for (size_t cc = 0; cc < indices.size (); ++cc)
00351   {
00352     // Iterate over each idx
00353     for (size_t i = 0; i < indices[cc].indices.size (); ++i)
00354     {
00355       // Iterate over each dimension
00356       pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (cloud_in.points[indices[cc].indices[i]], cloud_out.points[cp]));
00357       ++cp;
00358     }
00359   }
00360 }
00361 
00363 template <typename PointIn1T, typename PointIn2T, typename PointOutT> void
00364 pcl::concatenateFields (const pcl::PointCloud<PointIn1T> &cloud1_in,
00365                         const pcl::PointCloud<PointIn2T> &cloud2_in,
00366                         pcl::PointCloud<PointOutT> &cloud_out)
00367 {
00368   typedef typename pcl::traits::fieldList<PointIn1T>::type FieldList1;
00369   typedef typename pcl::traits::fieldList<PointIn2T>::type FieldList2;
00370 
00371   if (cloud1_in.points.size () != cloud2_in.points.size ())
00372   {
00373     PCL_ERROR ("[pcl::concatenateFields] The number of points in the two input datasets differs!\n");
00374     return;
00375   }
00376 
00377   // Resize the output dataset
00378   cloud_out.points.resize (cloud1_in.points.size ());
00379   cloud_out.header   = cloud1_in.header;
00380   cloud_out.width    = cloud1_in.width;
00381   cloud_out.height   = cloud1_in.height;
00382   if (!cloud1_in.is_dense || !cloud2_in.is_dense)
00383     cloud_out.is_dense = false;
00384   else
00385     cloud_out.is_dense = true;
00386 
00387   // Iterate over each point
00388   for (size_t i = 0; i < cloud_out.points.size (); ++i)
00389   {
00390     // Iterate over each dimension
00391     pcl::for_each_type <FieldList1> (pcl::NdConcatenateFunctor <PointIn1T, PointOutT> (cloud1_in.points[i], cloud_out.points[i]));
00392     pcl::for_each_type <FieldList2> (pcl::NdConcatenateFunctor <PointIn2T, PointOutT> (cloud2_in.points[i], cloud_out.points[i]));
00393   }
00394 }
00395 
00396 #endif // PCL_IO_IMPL_IO_H_
00397 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:31