pcl_conversions.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2013, Open Source Robotics Foundation, Inc.
00005  * Copyright (c) 2010-2012, Willow Garage, Inc.
00006  * All rights reserved.
00007  *
00008  * Redistribution and use in source and binary forms, with or without
00009  * modification, are permitted provided that the following conditions
00010  * are met:
00011  *
00012  *  * Redistributions of source code must retain the above copyright
00013  *    notice, this list of conditions and the following disclaimer.
00014  *  * Redistributions in binary form must reproduce the above
00015  *    copyright notice, this list of conditions and the following
00016  *    disclaimer in the documentation and/or other materials provided
00017  *    with the distribution.
00018  *  * Neither the name of Open Source Robotics Foundation, Inc. nor
00019  *    the names of its contributors may be used to endorse or promote
00020  *    products derived from this software without specific prior
00021  *    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 
00037 #ifndef PCL_CONVERSIONS_H__
00038 #define PCL_CONVERSIONS_H__
00039 
00040 #include <vector>
00041 
00042 #include <ros/ros.h>
00043 
00044 #include <pcl/conversions.h>
00045 
00046 #include <pcl/PCLHeader.h>
00047 #include <std_msgs/Header.h>
00048 
00049 #include <pcl/PCLImage.h>
00050 #include <sensor_msgs/Image.h>
00051 
00052 #include <pcl/PCLPointField.h>
00053 #include <sensor_msgs/PointField.h>
00054 
00055 #include <pcl/PCLPointCloud2.h>
00056 #include <sensor_msgs/PointCloud2.h>
00057 
00058 #include <pcl/PointIndices.h>
00059 #include <pcl_msgs/PointIndices.h>
00060 
00061 #include <pcl/ModelCoefficients.h>
00062 #include <pcl_msgs/ModelCoefficients.h>
00063 
00064 #include <pcl/Vertices.h>
00065 #include <pcl_msgs/Vertices.h>
00066 
00067 #include <pcl/PolygonMesh.h>
00068 #include <pcl_msgs/PolygonMesh.h>
00069 
00070 #include <pcl/io/pcd_io.h>
00071 
00072 #include <Eigen/StdVector>
00073 #include <Eigen/Geometry>
00074 
00075 namespace pcl_conversions {
00076 
00079   inline
00080   void fromPCL(const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
00081   {
00082     header.stamp.fromNSec(pcl_header.stamp * 1000ull);  // Convert from us to ns
00083     header.seq = pcl_header.seq;
00084     header.frame_id = pcl_header.frame_id;
00085   }
00086 
00087   inline
00088   void toPCL(const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
00089   {
00090     pcl_header.stamp = header.stamp.toNSec() / 1000ull;  // Convert from ns to us
00091     pcl_header.seq = header.seq;
00092     pcl_header.frame_id = header.frame_id;
00093   }
00094 
00095   inline
00096   std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
00097   {
00098     std_msgs::Header header;
00099     fromPCL(pcl_header, header);
00100     return header;
00101   }
00102 
00103   inline
00104   pcl::PCLHeader toPCL(const std_msgs::Header &header)
00105   {
00106     pcl::PCLHeader pcl_header;
00107     toPCL(header, pcl_header);
00108     return pcl_header;
00109   }
00110 
00113   inline
00114   void copyPCLImageMetaData(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
00115   {
00116     fromPCL(pcl_image.header, image.header);
00117     image.height = pcl_image.height;
00118     image.width = pcl_image.width;
00119     image.encoding = pcl_image.encoding;
00120     image.is_bigendian = pcl_image.is_bigendian;
00121     image.step = pcl_image.step;
00122   }
00123 
00124   inline
00125   void fromPCL(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
00126   {
00127     copyPCLImageMetaData(pcl_image, image);
00128     image.data = pcl_image.data;
00129   }
00130 
00131   inline
00132   void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
00133   {
00134     copyPCLImageMetaData(pcl_image, image);
00135     image.data.swap(pcl_image.data);
00136   }
00137 
00138   inline
00139   void copyImageMetaData(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
00140   {
00141     toPCL(image.header, pcl_image.header);
00142     pcl_image.height = image.height;
00143     pcl_image.width = image.width;
00144     pcl_image.encoding = image.encoding;
00145     pcl_image.is_bigendian = image.is_bigendian;
00146     pcl_image.step = image.step;
00147   }
00148 
00149   inline
00150   void toPCL(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
00151   {
00152     copyImageMetaData(image, pcl_image);
00153     pcl_image.data = image.data;
00154   }
00155 
00156   inline
00157   void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
00158   {
00159     copyImageMetaData(image, pcl_image);
00160     pcl_image.data.swap(image.data);
00161   }
00162 
00165   inline
00166   void fromPCL(const pcl::PCLPointField &pcl_pf, sensor_msgs::PointField &pf)
00167   {
00168     pf.name = pcl_pf.name;
00169     pf.offset = pcl_pf.offset;
00170     pf.datatype = pcl_pf.datatype;
00171     pf.count = pcl_pf.count;
00172   }
00173 
00174   inline
00175   void fromPCL(const std::vector<pcl::PCLPointField> &pcl_pfs, std::vector<sensor_msgs::PointField> &pfs)
00176   {
00177     pfs.resize(pcl_pfs.size());
00178     std::vector<pcl::PCLPointField>::const_iterator it = pcl_pfs.begin();
00179     int i = 0;
00180     for(; it != pcl_pfs.end(); ++it, ++i) {
00181       fromPCL(*(it), pfs[i]);
00182     }
00183   }
00184 
00185   inline
00186   void toPCL(const sensor_msgs::PointField &pf, pcl::PCLPointField &pcl_pf)
00187   {
00188     pcl_pf.name = pf.name;
00189     pcl_pf.offset = pf.offset;
00190     pcl_pf.datatype = pf.datatype;
00191     pcl_pf.count = pf.count;
00192   }
00193 
00194   inline
00195   void toPCL(const std::vector<sensor_msgs::PointField> &pfs, std::vector<pcl::PCLPointField> &pcl_pfs)
00196   {
00197     pcl_pfs.resize(pfs.size());
00198     std::vector<sensor_msgs::PointField>::const_iterator it = pfs.begin();
00199     int i = 0;
00200     for(; it != pfs.end(); ++it, ++i) {
00201       toPCL(*(it), pcl_pfs[i]);
00202     }
00203   }
00204 
00207   inline
00208   void copyPCLPointCloud2MetaData(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
00209   {
00210     fromPCL(pcl_pc2.header, pc2.header);
00211     pc2.height = pcl_pc2.height;
00212     pc2.width = pcl_pc2.width;
00213     fromPCL(pcl_pc2.fields, pc2.fields);
00214     pc2.is_bigendian = pcl_pc2.is_bigendian;
00215     pc2.point_step = pcl_pc2.point_step;
00216     pc2.row_step = pcl_pc2.row_step;
00217     pc2.is_dense = pcl_pc2.is_dense;
00218   }
00219 
00220   inline
00221   void fromPCL(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
00222   {
00223     copyPCLPointCloud2MetaData(pcl_pc2, pc2);
00224     pc2.data = pcl_pc2.data;
00225   }
00226 
00227   inline
00228   void moveFromPCL(pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
00229   {
00230     copyPCLPointCloud2MetaData(pcl_pc2, pc2);
00231     pc2.data.swap(pcl_pc2.data);
00232   }
00233 
00234   inline
00235   void copyPointCloud2MetaData(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
00236   {
00237     toPCL(pc2.header, pcl_pc2.header);
00238     pcl_pc2.height = pc2.height;
00239     pcl_pc2.width = pc2.width;
00240     toPCL(pc2.fields, pcl_pc2.fields);
00241     pcl_pc2.is_bigendian = pc2.is_bigendian;
00242     pcl_pc2.point_step = pc2.point_step;
00243     pcl_pc2.row_step = pc2.row_step;
00244     pcl_pc2.is_dense = pc2.is_dense;
00245   }
00246 
00247   inline
00248   void toPCL(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
00249   {
00250     copyPointCloud2MetaData(pc2, pcl_pc2);
00251     pcl_pc2.data = pc2.data;
00252   }
00253 
00254   inline
00255   void moveToPCL(sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
00256   {
00257     copyPointCloud2MetaData(pc2, pcl_pc2);
00258     pcl_pc2.data.swap(pc2.data);
00259   }
00260 
00263   inline
00264   void fromPCL(const pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
00265   {
00266     fromPCL(pcl_pi.header, pi.header);
00267     pi.indices = pcl_pi.indices;
00268   }
00269 
00270   inline
00271   void moveFromPCL(pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
00272   {
00273     fromPCL(pcl_pi.header, pi.header);
00274     pi.indices.swap(pcl_pi.indices);
00275   }
00276 
00277   inline
00278   void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
00279   {
00280     toPCL(pi.header, pcl_pi.header);
00281     pcl_pi.indices = pi.indices;
00282   }
00283 
00284   inline
00285   void moveToPCL(pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
00286   {
00287     toPCL(pi.header, pcl_pi.header);
00288     pcl_pi.indices.swap(pi.indices);
00289   }
00290 
00293   inline
00294   void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
00295   {
00296     fromPCL(pcl_mc.header, mc.header);
00297     mc.values = pcl_mc.values;
00298   }
00299 
00300   inline
00301   void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
00302   {
00303     fromPCL(pcl_mc.header, mc.header);
00304     mc.values.swap(pcl_mc.values);
00305   }
00306 
00307   inline
00308   void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
00309   {
00310     toPCL(mc.header, pcl_mc.header);
00311     pcl_mc.values = mc.values;
00312   }
00313 
00314   inline
00315   void moveToPCL(pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
00316   {
00317     toPCL(mc.header, pcl_mc.header);
00318     pcl_mc.values.swap(mc.values);
00319   }
00320 
00323   inline
00324   void fromPCL(const pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
00325   {
00326     vert.vertices = pcl_vert.vertices;
00327   }
00328 
00329   inline
00330   void fromPCL(const std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
00331   {
00332     verts.resize(pcl_verts.size());
00333     std::vector<pcl::Vertices>::const_iterator it = pcl_verts.begin();
00334     std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
00335     for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
00336       fromPCL(*(it), *(jt));
00337     }
00338   }
00339 
00340   inline
00341   void moveFromPCL(pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
00342   {
00343     vert.vertices.swap(pcl_vert.vertices);
00344   }
00345 
00346   inline
00347   void fromPCL(std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
00348   {
00349     verts.resize(pcl_verts.size());
00350     std::vector<pcl::Vertices>::iterator it = pcl_verts.begin();
00351     std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
00352     for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
00353       moveFromPCL(*(it), *(jt));
00354     }
00355   }
00356 
00357   inline
00358   void toPCL(const pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
00359   {
00360     pcl_vert.vertices = vert.vertices;
00361   }
00362 
00363   inline
00364   void toPCL(const std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
00365   {
00366     pcl_verts.resize(verts.size());
00367     std::vector<pcl_msgs::Vertices>::const_iterator it = verts.begin();
00368     std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
00369     for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
00370       toPCL(*(it), *(jt));
00371     }
00372   }
00373 
00374   inline
00375   void moveToPCL(pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
00376   {
00377     pcl_vert.vertices.swap(vert.vertices);
00378   }
00379 
00380   inline
00381   void moveToPCL(std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
00382   {
00383     pcl_verts.resize(verts.size());
00384     std::vector<pcl_msgs::Vertices>::iterator it = verts.begin();
00385     std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
00386     for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
00387       moveToPCL(*(it), *(jt));
00388     }
00389   }
00390 
00393   inline
00394   void fromPCL(const pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
00395   {
00396     fromPCL(pcl_mesh.header, mesh.header);
00397     fromPCL(pcl_mesh.cloud, mesh.cloud);
00398     fromPCL(pcl_mesh.polygons, mesh.polygons);
00399   }
00400 
00401   inline
00402   void moveFromPCL(pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
00403   {
00404     fromPCL(pcl_mesh.header, mesh.header);
00405     moveFromPCL(pcl_mesh.cloud, mesh.cloud);
00406     moveFromPCL(pcl_mesh.cloud, mesh.cloud);
00407   }
00408 
00409   inline
00410   void toPCL(const pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
00411   {
00412     toPCL(mesh.header, pcl_mesh.header);
00413     toPCL(mesh.cloud, pcl_mesh.cloud);
00414     toPCL(mesh.polygons, pcl_mesh.polygons);
00415   }
00416 
00417   inline
00418   void moveToPCL(pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
00419   {
00420     toPCL(mesh.header, pcl_mesh.header);
00421     moveToPCL(mesh.cloud, pcl_mesh.cloud);
00422     moveToPCL(mesh.polygons, pcl_mesh.polygons);
00423   }
00424 
00425 } // namespace pcl_conversions
00426 
00427 namespace pcl {
00428 
00431   inline int getFieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
00432   {
00433     // Get the index we need
00434     for (size_t d = 0; d < cloud.fields.size(); ++d) {
00435       if (cloud.fields[d].name == field_name) {
00436         return (static_cast<int>(d));
00437       }
00438     }
00439     return (-1);
00440   }
00441 
00444   inline std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
00445   {
00446     std::string result;
00447     for (size_t i = 0; i < cloud.fields.size () - 1; ++i) {
00448       result += cloud.fields[i].name + " ";
00449     }
00450     result += cloud.fields[cloud.fields.size () - 1].name;
00451     return (result);
00452   }
00453 
00456   inline
00457   void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
00458   {
00459     pcl::PCLPointCloud2 pcl_cloud;
00460     pcl_conversions::toPCL(cloud, pcl_cloud);
00461     pcl::PCLImage pcl_image;
00462     pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
00463     pcl_conversions::moveFromPCL(pcl_image, image);
00464   }
00465 
00466   inline
00467   void moveToROSMsg(sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
00468   {
00469     pcl::PCLPointCloud2 pcl_cloud;
00470     pcl_conversions::moveToPCL(cloud, pcl_cloud);
00471     pcl::PCLImage pcl_image;
00472     pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
00473     pcl_conversions::moveFromPCL(pcl_image, image);
00474   }
00475 
00476   template<typename T> void
00477   toROSMsg (const pcl::PointCloud<T> &cloud, sensor_msgs::Image& msg)
00478   {
00479     // Ease the user's burden on specifying width/height for unorganized datasets
00480     if (cloud.width == 0 && cloud.height == 0)
00481     {
00482       throw std::runtime_error("Needs to be a dense like cloud!!");
00483     }
00484     else
00485     {
00486       if (cloud.points.size () != cloud.width * cloud.height)
00487         throw std::runtime_error("The width and height do not match the cloud size!");
00488       msg.height = cloud.height;
00489       msg.width = cloud.width;
00490     }
00491 
00492     // sensor_msgs::image_encodings::BGR8;
00493     msg.encoding = "bgr8";
00494     msg.step = msg.width * sizeof (uint8_t) * 3;
00495     msg.data.resize (msg.step * msg.height);
00496     for (size_t y = 0; y < cloud.height; y++)
00497     {
00498       for (size_t x = 0; x < cloud.width; x++)
00499       {
00500         uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
00501         memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t));
00502       }
00503     }
00504   }
00505 
00508   template<typename T>
00509   void toROSMsg(const pcl::PointCloud<T> &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
00510   {
00511     pcl::PCLPointCloud2 pcl_pc2;
00512     pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
00513     pcl_conversions::moveFromPCL(pcl_pc2, cloud);
00514   }
00515 
00516   template<typename T>
00517   void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
00518   {
00519     pcl::PCLPointCloud2 pcl_pc2;
00520     pcl_conversions::toPCL(cloud, pcl_pc2);
00521     pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
00522   }
00523 
00524   template<typename T>
00525   void moveFromROSMsg(sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
00526   {
00527     pcl::PCLPointCloud2 pcl_pc2;
00528     pcl_conversions::moveToPCL(cloud, pcl_pc2);
00529     pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
00530   }
00531 
00534   template<typename PointT>
00535   void createMapping(const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
00536   {
00537     std::vector<pcl::PCLPointField> pcl_msg_fields;
00538     pcl_conversions::toPCL(msg_fields, pcl_msg_fields);
00539     return createMapping<PointT>(pcl_msg_fields, field_map);
00540   }
00541 
00542   namespace io {
00543 
00546     inline int
00547     savePCDFile(const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
00548                 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00549                 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00550                 const bool binary_mode = false)
00551     {
00552       pcl::PCLPointCloud2 pcl_cloud;
00553       pcl_conversions::toPCL(cloud, pcl_cloud);
00554       return pcl::io::savePCDFile(file_name, pcl_cloud, origin, orientation, binary_mode);
00555     }
00556 
00557     inline int
00558     destructiveSavePCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud,
00559                            const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00560                            const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00561                            const bool binary_mode = false)
00562     {
00563       pcl::PCLPointCloud2 pcl_cloud;
00564       pcl_conversions::moveToPCL(cloud, pcl_cloud);
00565       return pcl::io::savePCDFile(file_name, pcl_cloud, origin, orientation, binary_mode);
00566     }
00567 
00570     inline int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
00571     {
00572       pcl::PCLPointCloud2 pcl_cloud;
00573       int ret = pcl::io::loadPCDFile(file_name, pcl_cloud);
00574       pcl_conversions::moveFromPCL(pcl_cloud, cloud);
00575       return ret;
00576     }
00577 
00578   } // namespace io
00579 
00582   inline
00583   bool concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1,
00584                               const sensor_msgs::PointCloud2 &cloud2,
00585                               sensor_msgs::PointCloud2 &cloud_out)
00586   {
00587     //if one input cloud has no points, but the other input does, just return the cloud with points
00588     if (cloud1.width * cloud1.height == 0 && cloud2.width * cloud2.height > 0)
00589     {
00590       cloud_out = cloud2;
00591       return (true);
00592     }
00593     else if (cloud1.width*cloud1.height > 0 && cloud2.width*cloud2.height == 0)
00594     {
00595       cloud_out = cloud1;
00596       return (true);
00597     }
00598 
00599     bool strip = false;
00600     for (size_t i = 0; i < cloud1.fields.size (); ++i)
00601       if (cloud1.fields[i].name == "_")
00602         strip = true;
00603 
00604     for (size_t i = 0; i < cloud2.fields.size (); ++i)
00605       if (cloud2.fields[i].name == "_")
00606         strip = true;
00607 
00608     if (!strip && cloud1.fields.size () != cloud2.fields.size ())
00609     {
00610       PCL_ERROR ("[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.fields.size (), cloud2.fields.size ());
00611       return (false);
00612     }
00613 
00614     // Copy cloud1 into cloud_out
00615     cloud_out = cloud1;
00616     size_t nrpts = cloud_out.data.size ();
00617     // Height = 1 => no more organized
00618     cloud_out.width    = cloud1.width * cloud1.height + cloud2.width * cloud2.height;
00619     cloud_out.height   = 1;
00620     if (!cloud1.is_dense || !cloud2.is_dense)
00621       cloud_out.is_dense = false;
00622     else
00623       cloud_out.is_dense = true;
00624 
00625     // We need to strip the extra padding fields
00626     if (strip)
00627     {
00628       // Get the field sizes for the second cloud
00629       std::vector<sensor_msgs::PointField> fields2;
00630       std::vector<int> fields2_sizes;
00631       for (size_t j = 0; j < cloud2.fields.size (); ++j)
00632       {
00633         if (cloud2.fields[j].name == "_")
00634           continue;
00635 
00636         fields2_sizes.push_back (cloud2.fields[j].count *
00637                                  pcl::getFieldSize (cloud2.fields[j].datatype));
00638         fields2.push_back (cloud2.fields[j]);
00639       }
00640 
00641       cloud_out.data.resize (nrpts + (cloud2.width * cloud2.height) * cloud_out.point_step);
00642 
00643       // Copy the second cloud
00644       for (size_t cp = 0; cp < cloud2.width * cloud2.height; ++cp)
00645       {
00646         int i = 0;
00647         for (size_t j = 0; j < fields2.size (); ++j)
00648         {
00649           if (cloud1.fields[i].name == "_")
00650           {
00651             ++i;
00652             continue;
00653           }
00654 
00655           // We're fine with the special RGB vs RGBA use case
00656           if ((cloud1.fields[i].name == "rgb" && fields2[j].name == "rgba") ||
00657               (cloud1.fields[i].name == "rgba" && fields2[j].name == "rgb") ||
00658               (cloud1.fields[i].name == fields2[j].name))
00659           {
00660             memcpy (reinterpret_cast<char*> (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]),
00661                     reinterpret_cast<const char*> (&cloud2.data[cp * cloud2.point_step + cloud2.fields[j].offset]),
00662                     fields2_sizes[j]);
00663             ++i;  // increment the field size i
00664           }
00665         }
00666       }
00667     }
00668     else
00669     {
00670       for (size_t i = 0; i < cloud1.fields.size (); ++i)
00671       {
00672         // We're fine with the special RGB vs RGBA use case
00673         if ((cloud1.fields[i].name == "rgb" && cloud2.fields[i].name == "rgba") ||
00674             (cloud1.fields[i].name == "rgba" && cloud2.fields[i].name == "rgb"))
00675           continue;
00676         // Otherwise we need to make sure the names are the same
00677         if (cloud1.fields[i].name != cloud2.fields[i].name)
00678         {
00679           PCL_ERROR ("[pcl::concatenatePointCloud] Name of field %d in cloud1, %s, does not match name in cloud2, %s\n", i, cloud1.fields[i].name.c_str (), cloud2.fields[i].name.c_str ());
00680           return (false);
00681         }
00682       }
00683       cloud_out.data.resize (nrpts + cloud2.data.size ());
00684       memcpy (&cloud_out.data[nrpts], &cloud2.data[0], cloud2.data.size ());
00685     }
00686     return (true);
00687   }
00688 
00689 } // namespace pcl
00690 
00691 namespace ros
00692 {
00693   template<>
00694   struct DefaultMessageCreator<pcl::PCLPointCloud2>
00695   {
00696     boost::shared_ptr<pcl::PCLPointCloud2> operator() ()
00697     {
00698       boost::shared_ptr<pcl::PCLPointCloud2> msg(new pcl::PCLPointCloud2());
00699       return msg;
00700     }
00701   };
00702 
00703   namespace message_traits
00704   {
00705     template<>
00706     struct MD5Sum<pcl::PCLPointCloud2>
00707     {
00708       static const char* value() { return MD5Sum<sensor_msgs::PointCloud2>::value(); }
00709       static const char* value(const pcl::PCLPointCloud2&) { return value(); }
00710 
00711       static const uint64_t static_value1 = MD5Sum<sensor_msgs::PointCloud2>::static_value1;
00712       static const uint64_t static_value2 = MD5Sum<sensor_msgs::PointCloud2>::static_value2;
00713 
00714       // If the definition of sensor_msgs/PointCloud2 changes, we'll get a compile error here.
00715       ROS_STATIC_ASSERT(static_value1 == 0x1158d486dd51d683ULL);
00716       ROS_STATIC_ASSERT(static_value2 == 0xce2f1be655c3c181ULL);
00717     };
00718 
00719     template<>
00720     struct DataType<pcl::PCLPointCloud2>
00721     {
00722       static const char* value() { return DataType<sensor_msgs::PointCloud2>::value(); }
00723       static const char* value(const pcl::PCLPointCloud2&) { return value(); }
00724     };
00725 
00726     template<>
00727     struct Definition<pcl::PCLPointCloud2>
00728     {
00729       static const char* value() { return Definition<sensor_msgs::PointCloud2>::value(); }
00730       static const char* value(const pcl::PCLPointCloud2&) { return value(); }
00731     };
00732 
00733     template<> struct HasHeader<pcl::PCLPointCloud2> : TrueType {};
00734   } // namespace ros::message_traits
00735 
00736   namespace serialization
00737   {
00738     /*
00739      * Provide a custom serialization for pcl::PCLPointCloud2
00740      */
00741     template<>
00742     struct Serializer<pcl::PCLPointCloud2>
00743     {
00744       template<typename Stream>
00745       inline static void write(Stream& stream, const pcl::PCLPointCloud2& m)
00746       {
00747         std_msgs::Header header;
00748         pcl_conversions::fromPCL(m.header, header);
00749         stream.next(header);
00750         stream.next(m.height);
00751         stream.next(m.width);
00752         std::vector<sensor_msgs::PointField> pfs;
00753         pcl_conversions::fromPCL(m.fields, pfs);
00754         stream.next(pfs);
00755         stream.next(m.is_bigendian);
00756         stream.next(m.point_step);
00757         stream.next(m.row_step);
00758         stream.next(m.data);
00759         stream.next(m.is_dense);
00760       }
00761 
00762       template<typename Stream>
00763       inline static void read(Stream& stream, pcl::PCLPointCloud2& m)
00764       {
00765         std_msgs::Header header;
00766         stream.next(header);
00767         pcl_conversions::toPCL(header, m.header);
00768         stream.next(m.height);
00769         stream.next(m.width);
00770         std::vector<sensor_msgs::PointField> pfs;
00771         stream.next(pfs);
00772         pcl_conversions::toPCL(pfs, m.fields);
00773         stream.next(m.is_bigendian);
00774         stream.next(m.point_step);
00775         stream.next(m.row_step);
00776         stream.next(m.data);
00777         stream.next(m.is_dense);
00778       }
00779 
00780       inline static uint32_t serializedLength(const pcl::PCLPointCloud2& m)
00781       {
00782         uint32_t length = 0;
00783 
00784         std_msgs::Header header;
00785         pcl_conversions::fromPCL(m.header, header);
00786         length += serializationLength(header);
00787         length += 4; // height
00788         length += 4; // width
00789         std::vector<sensor_msgs::PointField> pfs;
00790         pcl_conversions::fromPCL(m.fields, pfs);
00791         length += serializationLength(pfs); // fields
00792         length += 1; // is_bigendian
00793         length += 4; // point_step
00794         length += 4; // row_step
00795         length += 4; // data's size
00796         length += m.data.size() * sizeof(pcl::uint8_t);
00797         length += 1; // is_dense
00798 
00799         return length;
00800       }
00801     };
00802 
00803     /*
00804      * Provide a custom serialization for pcl::PCLPointField
00805      */
00806     template<>
00807     struct Serializer<pcl::PCLPointField>
00808     {
00809       template<typename Stream>
00810       inline static void write(Stream& stream, const pcl::PCLPointField& m)
00811       {
00812         stream.next(m.name);
00813         stream.next(m.offset);
00814         stream.next(m.datatype);
00815         stream.next(m.count);
00816       }
00817 
00818       template<typename Stream>
00819       inline static void read(Stream& stream, pcl::PCLPointField& m)
00820       {
00821         stream.next(m.name);
00822         stream.next(m.offset);
00823         stream.next(m.datatype);
00824         stream.next(m.count);
00825       }
00826 
00827       inline static uint32_t serializedLength(const pcl::PCLPointField& m)
00828       {
00829         uint32_t length = 0;
00830 
00831         length += serializationLength(m.name);
00832         length += serializationLength(m.offset);
00833         length += serializationLength(m.datatype);
00834         length += serializationLength(m.count);
00835 
00836         return length;
00837       }
00838     };
00839 
00840     /*
00841      * Provide a custom serialization for pcl::PCLHeader
00842      */
00843     template<>
00844     struct Serializer<pcl::PCLHeader>
00845     {
00846       template<typename Stream>
00847       inline static void write(Stream& stream, const pcl::PCLHeader& m)
00848       {
00849         std_msgs::Header header;
00850         pcl_conversions::fromPCL(m, header);
00851         stream.next(header);
00852       }
00853 
00854       template<typename Stream>
00855       inline static void read(Stream& stream, pcl::PCLHeader& m)
00856       {
00857         std_msgs::Header header;
00858         stream.next(header);
00859         pcl_conversions::toPCL(header, m);
00860       }
00861 
00862       inline static uint32_t serializedLength(const pcl::PCLHeader& m)
00863       {
00864         uint32_t length = 0;
00865 
00866         std_msgs::Header header;
00867         pcl_conversions::fromPCL(m, header);
00868         length += serializationLength(header);
00869 
00870         return length;
00871       }
00872     };
00873   } // namespace ros::serialization
00874 
00875 } // namespace ros
00876 
00877 
00878 #endif /* PCL_CONVERSIONS_H__ */


pcl_conversions
Author(s): William Woodall
autogenerated on Wed Aug 26 2015 15:21:09