00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 #ifndef PCL_COMMON_IO_H_
00042 #define PCL_COMMON_IO_H_
00043 
00044 #include <string>
00045 #include <pcl/pcl_base.h>
00046 #include <pcl/PointIndices.h>
00047 #include <pcl/conversions.h>
00048 #include <locale>
00049 
00050 namespace pcl
00051 {
00057   inline int
00058   getFieldIndex (const pcl::PCLPointCloud2 &cloud, const std::string &field_name)
00059   {
00060     
00061     for (size_t d = 0; d < cloud.fields.size (); ++d)
00062       if (cloud.fields[d].name == field_name)
00063         return (static_cast<int>(d));
00064     return (-1);
00065   }
00066 
00073   template <typename PointT> inline int 
00074   getFieldIndex (const pcl::PointCloud<PointT> &cloud, const std::string &field_name, 
00075                  std::vector<pcl::PCLPointField> &fields);
00076 
00082   template <typename PointT> inline int 
00083   getFieldIndex (const std::string &field_name, 
00084                  std::vector<pcl::PCLPointField> &fields);
00085 
00091   template <typename PointT> inline void 
00092   getFields (const pcl::PointCloud<PointT> &cloud, std::vector<pcl::PCLPointField> &fields);
00093 
00098   template <typename PointT> inline void 
00099   getFields (std::vector<pcl::PCLPointField> &fields);
00100 
00105   template <typename PointT> inline std::string 
00106   getFieldsList (const pcl::PointCloud<PointT> &cloud);
00107 
00112   inline std::string
00113   getFieldsList (const pcl::PCLPointCloud2 &cloud)
00114   {
00115     std::string result;
00116     for (size_t i = 0; i < cloud.fields.size () - 1; ++i)
00117       result += cloud.fields[i].name + " ";
00118     result += cloud.fields[cloud.fields.size () - 1].name;
00119     return (result);
00120   }
00121 
00126   inline int
00127   getFieldSize (const int datatype)
00128   {
00129     switch (datatype)
00130     {
00131       case pcl::PCLPointField::INT8:
00132       case pcl::PCLPointField::UINT8:
00133         return (1);
00134 
00135       case pcl::PCLPointField::INT16:
00136       case pcl::PCLPointField::UINT16:
00137         return (2);
00138 
00139       case pcl::PCLPointField::INT32:
00140       case pcl::PCLPointField::UINT32:
00141       case pcl::PCLPointField::FLOAT32:
00142         return (4);
00143 
00144       case pcl::PCLPointField::FLOAT64:
00145         return (8);
00146 
00147       default:
00148         return (0);
00149     }
00150   }
00151 
00156   PCL_EXPORTS void
00157   getFieldsSizes (const std::vector<pcl::PCLPointField> &fields,
00158                   std::vector<int> &field_sizes);
00159 
00165   inline int
00166   getFieldType (const int size, char type)
00167   {
00168     type = std::toupper (type, std::locale::classic ());
00169     switch (size)
00170     {
00171       case 1:
00172         if (type == 'I')
00173           return (pcl::PCLPointField::INT8);
00174         if (type == 'U')
00175           return (pcl::PCLPointField::UINT8);
00176 
00177       case 2:
00178         if (type == 'I')
00179           return (pcl::PCLPointField::INT16);
00180         if (type == 'U')
00181           return (pcl::PCLPointField::UINT16);
00182 
00183       case 4:
00184         if (type == 'I')
00185           return (pcl::PCLPointField::INT32);
00186         if (type == 'U')
00187           return (pcl::PCLPointField::UINT32);
00188         if (type == 'F')
00189           return (pcl::PCLPointField::FLOAT32);
00190 
00191       case 8:
00192         return (pcl::PCLPointField::FLOAT64);
00193 
00194       default:
00195         return (-1);
00196     }
00197   }
00198 
00203   inline char
00204   getFieldType (const int type)
00205   {
00206     switch (type)
00207     {
00208       case pcl::PCLPointField::INT8:
00209       case pcl::PCLPointField::INT16:
00210       case pcl::PCLPointField::INT32:
00211         return ('I');
00212 
00213       case pcl::PCLPointField::UINT8:
00214       case pcl::PCLPointField::UINT16:
00215       case pcl::PCLPointField::UINT32:
00216         return ('U');
00217 
00218       case pcl::PCLPointField::FLOAT32:
00219       case pcl::PCLPointField::FLOAT64:
00220         return ('F');
00221       default:
00222         return ('?');
00223     }
00224   }
00225 
00233   PCL_EXPORTS bool 
00234   concatenatePointCloud (const pcl::PCLPointCloud2 &cloud1,
00235                          const pcl::PCLPointCloud2 &cloud2,
00236                          pcl::PCLPointCloud2 &cloud_out);
00237 
00245   PCL_EXPORTS void 
00246   copyPointCloud (const pcl::PCLPointCloud2 &cloud_in,
00247                   const std::vector<int> &indices, 
00248                   pcl::PCLPointCloud2 &cloud_out);
00249 
00257   PCL_EXPORTS void 
00258   copyPointCloud (const pcl::PCLPointCloud2 &cloud_in,
00259                   const std::vector<int, Eigen::aligned_allocator<int> > &indices, 
00260                   pcl::PCLPointCloud2 &cloud_out);
00261 
00267   PCL_EXPORTS void 
00268   copyPointCloud (const pcl::PCLPointCloud2 &cloud_in,
00269                   pcl::PCLPointCloud2 &cloud_out);
00270 
00272   template <typename Point1T, typename Point2T> inline bool
00273   isSamePointType ()
00274   {
00275     return (typeid (Point1T) == typeid (Point2T));
00276   }
00277 
00285   template <typename PointT> void 
00286   copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00287                   const std::vector<int> &indices, 
00288                   pcl::PointCloud<PointT> &cloud_out);
00289  
00297   template <typename PointT> void 
00298   copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00299                   const std::vector<int, Eigen::aligned_allocator<int> > &indices, 
00300                   pcl::PointCloud<PointT> &cloud_out);
00301 
00309   template <typename PointT> void 
00310   copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00311                   const PointIndices &indices, 
00312                   pcl::PointCloud<PointT> &cloud_out);
00313 
00321   template <typename PointT> void 
00322   copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00323                   const std::vector<pcl::PointIndices> &indices, 
00324                   pcl::PointCloud<PointT> &cloud_out);
00325 
00331   template <typename PointInT, typename PointOutT> void 
00332   copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, 
00333                   pcl::PointCloud<PointOutT> &cloud_out);
00334 
00342   template <typename PointInT, typename PointOutT> void 
00343   copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, 
00344                   const std::vector<int> &indices, 
00345                   pcl::PointCloud<PointOutT> &cloud_out);
00346 
00354   template <typename PointInT, typename PointOutT> void 
00355   copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, 
00356                   const std::vector<int, Eigen::aligned_allocator<int> > &indices, 
00357                   pcl::PointCloud<PointOutT> &cloud_out);
00358 
00366   template <typename PointInT, typename PointOutT> void 
00367   copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, 
00368                   const PointIndices &indices, 
00369                   pcl::PointCloud<PointOutT> &cloud_out);
00370 
00378   template <typename PointInT, typename PointOutT> void 
00379   copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, 
00380                   const std::vector<pcl::PointIndices> &indices, 
00381                   pcl::PointCloud<PointOutT> &cloud_out);
00382 
00394   template <typename PointIn1T, typename PointIn2T, typename PointOutT> void 
00395   concatenateFields (const pcl::PointCloud<PointIn1T> &cloud1_in, 
00396                      const pcl::PointCloud<PointIn2T> &cloud2_in, 
00397                      pcl::PointCloud<PointOutT> &cloud_out);
00398 
00410   PCL_EXPORTS bool
00411   concatenateFields (const pcl::PCLPointCloud2 &cloud1_in,
00412                      const pcl::PCLPointCloud2 &cloud2_in,
00413                      pcl::PCLPointCloud2 &cloud_out);
00414 
00420   PCL_EXPORTS bool 
00421   getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out);
00422 
00429   PCL_EXPORTS bool 
00430   getEigenAsPointCloud (Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out);
00431   
00432   namespace io 
00433   {
00438     template <std::size_t N> void 
00439     swapByte (char* bytes);
00440 
00444     template <> inline void 
00445     swapByte<1> (char* bytes) { bytes[0] = bytes[0]; }
00446 
00447   
00451     template <> inline void 
00452     swapByte<2> (char* bytes) { std::swap (bytes[0], bytes[1]); }
00453   
00457     template <> inline void 
00458     swapByte<4> (char* bytes)
00459     {
00460       std::swap (bytes[0], bytes[3]);
00461       std::swap (bytes[1], bytes[2]);
00462     }
00463   
00467     template <> inline void 
00468     swapByte<8> (char* bytes)
00469     {
00470       std::swap (bytes[0], bytes[7]);
00471       std::swap (bytes[1], bytes[6]);
00472       std::swap (bytes[2], bytes[5]);
00473       std::swap (bytes[3], bytes[4]);
00474     }
00475   
00479     template <typename T> void 
00480     swapByte (T& value)
00481     {
00482       pcl::io::swapByte<sizeof(T)> (reinterpret_cast<char*> (&value));
00483     }
00484   }
00485 }
00486 
00487 #include <pcl/common/impl/io.hpp>
00488 
00489 #endif  //#ifndef PCL_COMMON_IO_H_
00490