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 #ifndef PCL_IO_IO_H_
00039 #define PCL_IO_IO_H_
00040
00041 #include <string>
00042 #include <boost/fusion/sequence/intrinsic/at_key.hpp>
00043 #include "pcl/pcl_base.h"
00044 #include "pcl/PointIndices.h"
00045 #include "pcl/ros/conversions.h"
00046 #include <locale>
00047
00048 namespace pcl
00049 {
00054 inline int
00055 getFieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
00056 {
00057
00058 for (size_t d = 0; d < cloud.fields.size (); ++d)
00059 if (cloud.fields[d].name == field_name)
00060 return (d);
00061 return (-1);
00062 }
00063
00069 template <typename PointT> inline int
00070 getFieldIndex (const pcl::PointCloud<PointT> &cloud, const std::string &field_name,
00071 std::vector<sensor_msgs::PointField> &fields);
00072
00077 template <typename PointT> inline void
00078 getFields (const pcl::PointCloud<PointT> &cloud, std::vector<sensor_msgs::PointField> &fields);
00079
00083 template <typename PointT> inline std::string
00084 getFieldsList (const pcl::PointCloud<PointT> &cloud);
00085
00089 inline std::string
00090 getFieldsList (const sensor_msgs::PointCloud2 &cloud)
00091 {
00092 std::string result;
00093 for (size_t i = 0; i < cloud.fields.size () - 1; ++i)
00094 result += cloud.fields[i].name + " ";
00095 result += cloud.fields[cloud.fields.size () - 1].name;
00096 return (result);
00097 }
00098
00102 inline int
00103 getFieldSize (int datatype)
00104 {
00105 switch (datatype)
00106 {
00107 case sensor_msgs::PointField::INT8:
00108 case sensor_msgs::PointField::UINT8:
00109 return (1);
00110
00111 case sensor_msgs::PointField::INT16:
00112 case sensor_msgs::PointField::UINT16:
00113 return (2);
00114
00115 case sensor_msgs::PointField::INT32:
00116 case sensor_msgs::PointField::UINT32:
00117 case sensor_msgs::PointField::FLOAT32:
00118 return (4);
00119
00120 case sensor_msgs::PointField::FLOAT64:
00121 return (8);
00122
00123 default:
00124 return (0);
00125 }
00126 }
00127
00132 inline int
00133 getFieldType (int size, char type)
00134 {
00135 type = std::toupper (type, std::locale::classic ());
00136 switch (size)
00137 {
00138 case 1:
00139 if (type == 'I')
00140 return (sensor_msgs::PointField::INT8);
00141 if (type == 'U')
00142 return (sensor_msgs::PointField::UINT8);
00143
00144 case 2:
00145 if (type == 'I')
00146 return (sensor_msgs::PointField::INT16);
00147 if (type == 'U')
00148 return (sensor_msgs::PointField::UINT16);
00149
00150 case 4:
00151 if (type == 'I')
00152 return (sensor_msgs::PointField::INT32);
00153 if (type == 'U')
00154 return (sensor_msgs::PointField::UINT32);
00155 if (type == 'F')
00156 return (sensor_msgs::PointField::FLOAT32);
00157
00158 case 8:
00159 return (sensor_msgs::PointField::FLOAT64);
00160
00161 default:
00162 return (-1);
00163 }
00164 }
00165
00169 inline char
00170 getFieldType (int type)
00171 {
00172 switch (type)
00173 {
00174 case sensor_msgs::PointField::INT8:
00175 case sensor_msgs::PointField::INT16:
00176 case sensor_msgs::PointField::INT32:
00177 return ('I');
00178
00179 case sensor_msgs::PointField::UINT8:
00180 case sensor_msgs::PointField::UINT16:
00181 case sensor_msgs::PointField::UINT32:
00182 return ('U');
00183
00184 case sensor_msgs::PointField::FLOAT32:
00185 case sensor_msgs::PointField::FLOAT64:
00186 return ('F');
00187 default:
00188 return ('?');
00189 }
00190 }
00191
00196 template <typename PointInT, typename PointOutT> void
00197 copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
00198 pcl::PointCloud<PointOutT> &cloud_out);
00199
00205 bool
00206 concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1,
00207 const sensor_msgs::PointCloud2 &cloud2,
00208 sensor_msgs::PointCloud2 &cloud_out);
00209
00215 void
00216 copyPointCloud (const sensor_msgs::PointCloud2 &cloud_in,
00217 const std::vector<int> &indices,
00218 sensor_msgs::PointCloud2 &cloud_out);
00219
00225 template <typename PointT> void
00226 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00227 const std::vector<int> &indices,
00228 pcl::PointCloud<PointT> &cloud_out);
00229
00235 template <typename PointT> void
00236 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00237 const PointIndices &indices,
00238 pcl::PointCloud<PointT> &cloud_out);
00239
00245 template <typename PointT> void
00246 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00247 const std::vector<pcl::PointIndices> &indices,
00248 pcl::PointCloud<PointT> &cloud_out);
00249
00255 template <typename PointIn1T, typename PointIn2T, typename PointOutT> void
00256 concatenateFields (const pcl::PointCloud<PointIn1T> &cloud1_in,
00257 const pcl::PointCloud<PointIn2T> &cloud2_in,
00258 pcl::PointCloud<PointOutT> &cloud_out);
00259
00264 bool
00265 getPointCloudAsEigen (const sensor_msgs::PointCloud2 &in, Eigen::MatrixXf &out);
00266
00272 bool
00273 getEigenAsPointCloud (Eigen::MatrixXf &in, sensor_msgs::PointCloud2 &out);
00274 }
00275
00276 #include "pcl/io/io.hpp"
00277
00278 #endif //#ifndef PCL_IO_IO_H_