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
00042
00043 #ifndef PCL_CONVERSIONS_H__
00044 #define PCL_CONVERSIONS_H__
00045
00046 #include <vector>
00047
00048 #include <std_msgs/Header.h>
00049 #include <sensor_msgs/Image.h>
00050 #include <sensor_msgs/PointField.h>
00051 #include <sensor_msgs/PointCloud2.h>
00052 #include <pcl/PointIndices.h>
00053 #include <pcl/ModelCoefficients.h>
00054 #include <pcl/Vertices.h>
00055 #include <pcl/PolygonMesh.h>
00056
00057
00058 namespace pcl_conversions {
00059
00062 inline
00063 void fromPCL(const std_msgs::Header &pcl_header, std_msgs::Header &header)
00064 {
00065 header = pcl_header;
00066 }
00067
00068 inline
00069 void toPCL(const std_msgs::Header &header, std_msgs::Header &pcl_header)
00070 {
00071 pcl_header = header;
00072 }
00073
00074 inline
00075 std_msgs::Header fromPCL(const std_msgs::Header &pcl_header)
00076 {
00077 return pcl_header;
00078 }
00079
00080 inline
00081 std_msgs::Header toPCL(const std_msgs::Header &header)
00082 {
00083 return header;
00084 }
00085
00088 inline
00089 void copyPCLImageMetaData(const sensor_msgs::Image &pcl_image, sensor_msgs::Image &image)
00090 {
00091 fromPCL(pcl_image.header, image.header);
00092 image.height = pcl_image.height;
00093 image.width = pcl_image.width;
00094 image.encoding = pcl_image.encoding;
00095 image.is_bigendian = pcl_image.is_bigendian;
00096 image.step = pcl_image.step;
00097 }
00098
00099 inline
00100 void fromPCL(const sensor_msgs::Image &pcl_image, sensor_msgs::Image &image)
00101 {
00102 image = pcl_image;
00103 }
00104
00105 inline
00106 void moveFromPCL(sensor_msgs::Image &pcl_image, sensor_msgs::Image &image)
00107 {
00108 copyPCLImageMetaData(pcl_image, image);
00109 image.data.swap(pcl_image.data);
00110 }
00111
00112 inline
00113 void copyImageMetaData(const sensor_msgs::Image &image, sensor_msgs::Image &pcl_image)
00114 {
00115 toPCL(image.header, pcl_image.header);
00116 pcl_image.height = image.height;
00117 pcl_image.width = image.width;
00118 pcl_image.encoding = image.encoding;
00119 pcl_image.is_bigendian = image.is_bigendian;
00120 pcl_image.step = image.step;
00121 }
00122
00123 inline
00124 void toPCL(const sensor_msgs::Image &image, sensor_msgs::Image &pcl_image)
00125 {
00126 pcl_image = image;
00127 }
00128
00129 inline
00130 void moveToPCL(sensor_msgs::Image &image, sensor_msgs::Image &pcl_image)
00131 {
00132 copyImageMetaData(image, pcl_image);
00133 pcl_image.data.swap(image.data);
00134 }
00135
00138 inline
00139 void fromPCL(const sensor_msgs::PointField &pcl_pf, sensor_msgs::PointField &pf)
00140 {
00141 pf = pcl_pf;
00142 }
00143
00144 inline
00145 void fromPCL(const std::vector<sensor_msgs::PointField> &pcl_pfs, std::vector<sensor_msgs::PointField> &pfs)
00146 {
00147 pfs = pcl_pfs;
00148 }
00149
00150 inline
00151 void toPCL(const sensor_msgs::PointField &pf, sensor_msgs::PointField &pcl_pf)
00152 {
00153 pcl_pf = pf;
00154 }
00155
00156 inline
00157 void toPCL(const std::vector<sensor_msgs::PointField> &pfs, std::vector<sensor_msgs::PointField> &pcl_pfs)
00158 {
00159 pcl_pfs = pfs;
00160 }
00161
00164 inline
00165 void copyPCLPointCloud2MetaData(const sensor_msgs::PointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
00166 {
00167 fromPCL(pcl_pc2.header, pc2.header);
00168 pc2.height = pcl_pc2.height;
00169 pc2.width = pcl_pc2.width;
00170 fromPCL(pcl_pc2.fields, pc2.fields);
00171 pc2.is_bigendian = pcl_pc2.is_bigendian;
00172 pc2.point_step = pcl_pc2.point_step;
00173 pc2.row_step = pcl_pc2.row_step;
00174 pc2.is_dense = pcl_pc2.is_dense;
00175 }
00176
00177 inline
00178 void fromPCL(const sensor_msgs::PointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
00179 {
00180 pc2 = pcl_pc2;
00181 }
00182
00183 inline
00184 void moveFromPCL(sensor_msgs::PointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
00185 {
00186 copyPCLPointCloud2MetaData(pcl_pc2, pc2);
00187 pc2.data.swap(pcl_pc2.data);
00188 }
00189
00190 inline
00191 void copyPointCloud2MetaData(const sensor_msgs::PointCloud2 &pc2, sensor_msgs::PointCloud2 &pcl_pc2)
00192 {
00193 toPCL(pc2.header, pcl_pc2.header);
00194 pcl_pc2.height = pc2.height;
00195 pcl_pc2.width = pc2.width;
00196 toPCL(pc2.fields, pcl_pc2.fields);
00197 pcl_pc2.is_bigendian = pc2.is_bigendian;
00198 pcl_pc2.point_step = pc2.point_step;
00199 pcl_pc2.row_step = pc2.row_step;
00200 pcl_pc2.is_dense = pc2.is_dense;
00201 }
00202
00203 inline
00204 void toPCL(const sensor_msgs::PointCloud2 &pc2, sensor_msgs::PointCloud2 &pcl_pc2)
00205 {
00206 pcl_pc2 = pc2;
00207 }
00208
00209 inline
00210 void moveToPCL(sensor_msgs::PointCloud2 &pc2, sensor_msgs::PointCloud2 &pcl_pc2)
00211 {
00212 copyPointCloud2MetaData(pc2, pcl_pc2);
00213 pcl_pc2.data.swap(pc2.data);
00214 }
00215
00218 inline
00219 void fromPCL(const pcl::PointIndices &pcl_pi, pcl::PointIndices &pi)
00220 {
00221 pi = pcl_pi;
00222 }
00223
00224 inline
00225 void moveFromPCL(pcl::PointIndices &pcl_pi, pcl::PointIndices &pi)
00226 {
00227 fromPCL(pcl_pi.header, pi.header);
00228 pi.indices.swap(pcl_pi.indices);
00229 }
00230
00231 inline
00232 void toPCL(const pcl::PointIndices &pi, pcl::PointIndices &pcl_pi)
00233 {
00234 pcl_pi = pi;
00235 }
00236
00237 inline
00238 void moveToPCL(pcl::PointIndices &pi, pcl::PointIndices &pcl_pi)
00239 {
00240 toPCL(pi.header, pcl_pi.header);
00241 pcl_pi.indices.swap(pi.indices);
00242 }
00243
00246 inline
00247 void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl::ModelCoefficients &mc)
00248 {
00249 mc = pcl_mc;
00250 }
00251
00252 inline
00253 void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl::ModelCoefficients &mc)
00254 {
00255 fromPCL(pcl_mc.header, mc.header);
00256 mc.values.swap(pcl_mc.values);
00257 }
00258
00259 inline
00260 void toPCL(const pcl::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
00261 {
00262 pcl_mc = mc;
00263 }
00264
00265 inline
00266 void moveToPCL(pcl::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
00267 {
00268 toPCL(mc.header, pcl_mc.header);
00269 pcl_mc.values.swap(mc.values);
00270 }
00271
00274 inline
00275 void fromPCL(const pcl::Vertices &pcl_vert, pcl::Vertices &vert)
00276 {
00277 vert = pcl_vert;
00278 }
00279
00280 inline
00281 void fromPCL(const std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl::Vertices> &verts)
00282 {
00283 verts = pcl_verts;
00284 }
00285
00286 inline
00287 void moveFromPCL(pcl::Vertices &pcl_vert, pcl::Vertices &vert)
00288 {
00289 vert.vertices.swap(pcl_vert.vertices);
00290 }
00291
00292 inline
00293 void moveFromPCL(std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl::Vertices> &verts)
00294 {
00295 verts.swap(pcl_verts);
00296 }
00297
00298 inline
00299 void toPCL(const pcl::Vertices &vert, pcl::Vertices &pcl_vert)
00300 {
00301 pcl_vert.vertices = vert.vertices;
00302 }
00303
00304 inline
00305 void toPCL(const std::vector<pcl::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
00306 {
00307 pcl_verts = verts;
00308 }
00309
00310 inline
00311 void moveToPCL(pcl::Vertices &vert, pcl::Vertices &pcl_vert)
00312 {
00313 pcl_vert.vertices.swap(vert.vertices);
00314 }
00315
00316 inline
00317 void moveToPCL(std::vector<pcl::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
00318 {
00319 pcl_verts.swap(verts);
00320 }
00321
00324 inline
00325 void fromPCL(const pcl::PolygonMesh &pcl_mesh, pcl::PolygonMesh &mesh)
00326 {
00327 mesh = pcl_mesh;
00328 }
00329
00330 inline
00331 void moveFromPCL(pcl::PolygonMesh &pcl_mesh, pcl::PolygonMesh &mesh)
00332 {
00333 fromPCL(pcl_mesh.header, mesh.header);
00334 moveFromPCL(pcl_mesh.cloud, mesh.cloud);
00335 moveFromPCL(pcl_mesh.cloud, mesh.cloud);
00336 }
00337
00338 inline
00339 void toPCL(const pcl::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
00340 {
00341 pcl_mesh = mesh;
00342 }
00343
00344 inline
00345 void moveToPCL(pcl::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
00346 {
00347 toPCL(mesh.header, pcl_mesh.header);
00348 moveToPCL(mesh.cloud, pcl_mesh.cloud);
00349 moveToPCL(mesh.polygons, pcl_mesh.polygons);
00350 }
00351
00352 }
00353
00354 #endif