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 #ifndef PCL_COMMON_IO_H_
00041 #define PCL_COMMON_IO_H_
00042
00043 #include <string>
00044 #include <boost/fusion/sequence/intrinsic/at_key.hpp>
00045 #include <pcl/pcl_base.h>
00046 #include <pcl/PointIndices.h>
00047 #include <pcl/ros/conversions.h>
00048 #include <locale>
00049
00050 namespace pcl
00051 {
00057 inline int
00058 getFieldIndex (const sensor_msgs::PointCloud2 &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<sensor_msgs::PointField> &fields);
00076
00082 template <typename PointT> inline int
00083 getFieldIndex (const std::string &field_name,
00084 std::vector<sensor_msgs::PointField> &fields);
00085
00091 template <typename PointT> inline void
00092 getFields (const pcl::PointCloud<PointT> &cloud, std::vector<sensor_msgs::PointField> &fields);
00093
00098 template <typename PointT> inline void
00099 getFields (std::vector<sensor_msgs::PointField> &fields);
00100
00105 template <typename PointT> inline std::string
00106 getFieldsList (const pcl::PointCloud<PointT> &cloud);
00107
00112 inline std::string
00113 getFieldsList (const sensor_msgs::PointCloud2 &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 sensor_msgs::PointField::INT8:
00132 case sensor_msgs::PointField::UINT8:
00133 return (1);
00134
00135 case sensor_msgs::PointField::INT16:
00136 case sensor_msgs::PointField::UINT16:
00137 return (2);
00138
00139 case sensor_msgs::PointField::INT32:
00140 case sensor_msgs::PointField::UINT32:
00141 case sensor_msgs::PointField::FLOAT32:
00142 return (4);
00143
00144 case sensor_msgs::PointField::FLOAT64:
00145 return (8);
00146
00147 default:
00148 return (0);
00149 }
00150 }
00151
00156 PCL_EXPORTS void
00157 getFieldsSizes (const std::vector<sensor_msgs::PointField> &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 (sensor_msgs::PointField::INT8);
00174 if (type == 'U')
00175 return (sensor_msgs::PointField::UINT8);
00176
00177 case 2:
00178 if (type == 'I')
00179 return (sensor_msgs::PointField::INT16);
00180 if (type == 'U')
00181 return (sensor_msgs::PointField::UINT16);
00182
00183 case 4:
00184 if (type == 'I')
00185 return (sensor_msgs::PointField::INT32);
00186 if (type == 'U')
00187 return (sensor_msgs::PointField::UINT32);
00188 if (type == 'F')
00189 return (sensor_msgs::PointField::FLOAT32);
00190
00191 case 8:
00192 return (sensor_msgs::PointField::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 sensor_msgs::PointField::INT8:
00209 case sensor_msgs::PointField::INT16:
00210 case sensor_msgs::PointField::INT32:
00211 return ('I');
00212
00213 case sensor_msgs::PointField::UINT8:
00214 case sensor_msgs::PointField::UINT16:
00215 case sensor_msgs::PointField::UINT32:
00216 return ('U');
00217
00218 case sensor_msgs::PointField::FLOAT32:
00219 case sensor_msgs::PointField::FLOAT64:
00220 return ('F');
00221 default:
00222 return ('?');
00223 }
00224 }
00225
00231 template <typename PointInT, typename PointOutT> void
00232 copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
00233 pcl::PointCloud<PointOutT> &cloud_out);
00234
00242 PCL_EXPORTS bool
00243 concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1,
00244 const sensor_msgs::PointCloud2 &cloud2,
00245 sensor_msgs::PointCloud2 &cloud_out);
00246
00253 PCL_EXPORTS void
00254 copyPointCloud (const sensor_msgs::PointCloud2 &cloud_in,
00255 const std::vector<int> &indices,
00256 sensor_msgs::PointCloud2 &cloud_out);
00257
00263 PCL_EXPORTS void
00264 copyPointCloud (const sensor_msgs::PointCloud2 &cloud_in,
00265 sensor_msgs::PointCloud2 &cloud_out);
00266
00273 template <typename PointT> void
00274 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00275 const std::vector<int> &indices,
00276 pcl::PointCloud<PointT> &cloud_out);
00283 template <typename PointT> void
00284 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00285 const std::vector<int, Eigen::aligned_allocator<int> > &indices,
00286 pcl::PointCloud<PointT> &cloud_out);
00287
00294 template <typename PointInT, typename PointOutT> void
00295 copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
00296 const std::vector<int> &indices,
00297 pcl::PointCloud<PointOutT> &cloud_out);
00298
00305 template <typename PointInT, typename PointOutT> void
00306 copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
00307 const std::vector<int, Eigen::aligned_allocator<int> > &indices,
00308 pcl::PointCloud<PointOutT> &cloud_out);
00309
00316 template <typename PointT> void
00317 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00318 const PointIndices &indices,
00319 pcl::PointCloud<PointT> &cloud_out);
00320
00327 template <typename PointInT, typename PointOutT> void
00328 copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
00329 const PointIndices &indices,
00330 pcl::PointCloud<PointOutT> &cloud_out);
00331
00338 template <typename PointT> void
00339 copyPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00340 const std::vector<pcl::PointIndices> &indices,
00341 pcl::PointCloud<PointT> &cloud_out);
00342
00349 template <typename PointInT, typename PointOutT> void
00350 copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
00351 const std::vector<pcl::PointIndices> &indices,
00352 pcl::PointCloud<PointOutT> &cloud_out);
00353
00365 template <typename PointIn1T, typename PointIn2T, typename PointOutT> void
00366 concatenateFields (const pcl::PointCloud<PointIn1T> &cloud1_in,
00367 const pcl::PointCloud<PointIn2T> &cloud2_in,
00368 pcl::PointCloud<PointOutT> &cloud_out);
00369
00381 PCL_EXPORTS bool
00382 concatenateFields (const sensor_msgs::PointCloud2 &cloud1_in,
00383 const sensor_msgs::PointCloud2 &cloud2_in,
00384 sensor_msgs::PointCloud2 &cloud_out);
00385
00391 PCL_EXPORTS bool
00392 getPointCloudAsEigen (const sensor_msgs::PointCloud2 &in, Eigen::MatrixXf &out);
00393
00400 PCL_EXPORTS bool
00401 getEigenAsPointCloud (Eigen::MatrixXf &in, sensor_msgs::PointCloud2 &out);
00402
00403 namespace io
00404 {
00409 template <std::size_t N> void
00410 swapByte (char* bytes);
00411
00415 template <> inline void
00416 swapByte<1> (char* bytes) { bytes[0] = bytes[0]; }
00417
00418
00422 template <> inline void
00423 swapByte<2> (char* bytes) { std::swap (bytes[0], bytes[1]); }
00424
00428 template <> inline void
00429 swapByte<4> (char* bytes)
00430 {
00431 std::swap (bytes[0], bytes[3]);
00432 std::swap (bytes[1], bytes[2]);
00433 }
00434
00438 template <> inline void
00439 swapByte<8> (char* bytes)
00440 {
00441 std::swap (bytes[0], bytes[7]);
00442 std::swap (bytes[1], bytes[6]);
00443 std::swap (bytes[2], bytes[5]);
00444 std::swap (bytes[3], bytes[4]);
00445 }
00446
00450 template <typename T> void
00451 swapByte (T& value)
00452 {
00453 pcl::io::swapByte<sizeof(T)> (reinterpret_cast<char*> (&value));
00454 }
00455 }
00456 }
00457
00458 #include <pcl/common/impl/io.hpp>
00459
00460 #endif //#ifndef PCL_COMMON_IO_H_
00461