/* * Software License Agreement (BSD License) * * Copyright (c) 2013, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Open Source Robotics Foundation, Inc. nor * the names of its contributors may be used to endorse or promote * products derived from this software without specific prior * written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef PCL_CONVERSIONS_H__ #define PCL_CONVERSIONS_H__ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include namespace pcl_conversions { /** PCLHeader <=> Header **/ inline void fromPCL(const pcl::PCLHeader &pcl_header, std_msgs::Header &header) { header.stamp.fromNSec(pcl_header.stamp * 1e3); // Convert from us to ns header.seq = pcl_header.seq; header.frame_id = pcl_header.frame_id; } inline void toPCL(const std_msgs::Header &header, pcl::PCLHeader &pcl_header) { pcl_header.stamp = header.stamp.toNSec() / 1e3; // Convert from ns to us pcl_header.seq = header.seq; pcl_header.frame_id = header.frame_id; } inline std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header) { std_msgs::Header header; fromPCL(pcl_header, header); return header; } inline pcl::PCLHeader toPCL(const std_msgs::Header &header) { pcl::PCLHeader pcl_header; toPCL(header, pcl_header); return pcl_header; } /** PCLImage <=> Image **/ inline void copyPCLImageMetaData(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image) { fromPCL(pcl_image.header, image.header); image.height = pcl_image.height; image.width = pcl_image.width; image.encoding = pcl_image.encoding; image.is_bigendian = pcl_image.is_bigendian; image.step = pcl_image.step; } inline void fromPCL(const pcl::PCLImage &pcl_image, sensor_msgs::Image &image) { copyPCLImageMetaData(pcl_image, image); image.data = pcl_image.data; } inline void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image) { copyPCLImageMetaData(pcl_image, image); image.data.swap(pcl_image.data); } inline void copyImageMetaData(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image) { toPCL(image.header, pcl_image.header); pcl_image.height = image.height; pcl_image.width = image.width; pcl_image.encoding = image.encoding; pcl_image.is_bigendian = image.is_bigendian; pcl_image.step = image.step; } inline void toPCL(const sensor_msgs::Image &image, pcl::PCLImage &pcl_image) { copyImageMetaData(image, pcl_image); pcl_image.data = image.data; } inline void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image) { copyImageMetaData(image, pcl_image); pcl_image.data.swap(image.data); } /** PCLPointField <=> PointField **/ inline void fromPCL(const pcl::PCLPointField &pcl_pf, sensor_msgs::PointField &pf) { pf.name = pcl_pf.name; pf.offset = pcl_pf.offset; pf.datatype = pcl_pf.datatype; pf.count = pcl_pf.count; } inline void fromPCL(const std::vector &pcl_pfs, std::vector &pfs) { pfs.resize(pcl_pfs.size()); std::vector::const_iterator it = pcl_pfs.begin(); int i = 0; for(; it != pcl_pfs.end(); ++it, ++i) { fromPCL(*(it), pfs[i]); } } inline void toPCL(const sensor_msgs::PointField &pf, pcl::PCLPointField &pcl_pf) { pcl_pf.name = pf.name; pcl_pf.offset = pf.offset; pcl_pf.datatype = pf.datatype; pcl_pf.count = pf.count; } inline void toPCL(const std::vector &pfs, std::vector &pcl_pfs) { pcl_pfs.resize(pfs.size()); std::vector::const_iterator it = pfs.begin(); int i = 0; for(; it != pfs.end(); ++it, ++i) { toPCL(*(it), pcl_pfs[i]); } } /** PCLPointCloud2 <=> PointCloud2 **/ inline void copyPCLPointCloud2MetaData(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2) { fromPCL(pcl_pc2.header, pc2.header); pc2.height = pcl_pc2.height; pc2.width = pcl_pc2.width; fromPCL(pcl_pc2.fields, pc2.fields); pc2.is_bigendian = pcl_pc2.is_bigendian; pc2.point_step = pcl_pc2.point_step; pc2.row_step = pcl_pc2.row_step; pc2.is_dense = pcl_pc2.is_dense; } inline void fromPCL(const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2) { copyPCLPointCloud2MetaData(pcl_pc2, pc2); pc2.data = pcl_pc2.data; } inline void moveFromPCL(pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2) { copyPCLPointCloud2MetaData(pcl_pc2, pc2); pc2.data.swap(pcl_pc2.data); } inline void copyPointCloud2MetaData(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2) { toPCL(pc2.header, pcl_pc2.header); pcl_pc2.height = pc2.height; pcl_pc2.width = pc2.width; toPCL(pc2.fields, pcl_pc2.fields); pcl_pc2.is_bigendian = pc2.is_bigendian; pcl_pc2.point_step = pc2.point_step; pcl_pc2.row_step = pc2.row_step; pcl_pc2.is_dense = pc2.is_dense; } inline void toPCL(const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2) { copyPointCloud2MetaData(pc2, pcl_pc2); pcl_pc2.data = pc2.data; } inline void moveToPCL(sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2) { copyPointCloud2MetaData(pc2, pcl_pc2); pcl_pc2.data.swap(pc2.data); } /** pcl::PointIndices <=> pcl_msgs::PointIndices **/ inline void fromPCL(const pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi) { fromPCL(pcl_pi.header, pi.header); pi.indices = pcl_pi.indices; } inline void moveFromPCL(pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi) { fromPCL(pcl_pi.header, pi.header); pi.indices.swap(pcl_pi.indices); } inline void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi) { toPCL(pi.header, pcl_pi.header); pcl_pi.indices = pi.indices; } inline void moveToPCL(pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi) { toPCL(pi.header, pcl_pi.header); pcl_pi.indices.swap(pi.indices); } /** pcl::ModelCoefficients <=> pcl_msgs::ModelCoefficients **/ inline void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc) { fromPCL(pcl_mc.header, mc.header); mc.values = pcl_mc.values; } inline void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc) { fromPCL(pcl_mc.header, mc.header); mc.values.swap(pcl_mc.values); } inline void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc) { toPCL(mc.header, pcl_mc.header); pcl_mc.values = mc.values; } inline void moveToPCL(pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc) { toPCL(mc.header, pcl_mc.header); pcl_mc.values.swap(mc.values); } /** pcl::Vertices <=> pcl_msgs::Vertices **/ inline void fromPCL(const pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert) { vert.vertices = pcl_vert.vertices; } inline void fromPCL(const std::vector &pcl_verts, std::vector &verts) { verts.resize(pcl_verts.size()); std::vector::const_iterator it = pcl_verts.begin(); std::vector::iterator jt = verts.begin(); for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) { fromPCL(*(it), *(jt)); } } inline void moveFromPCL(pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert) { vert.vertices.swap(pcl_vert.vertices); } inline void fromPCL(std::vector &pcl_verts, std::vector &verts) { verts.resize(pcl_verts.size()); std::vector::iterator it = pcl_verts.begin(); std::vector::iterator jt = verts.begin(); for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) { moveFromPCL(*(it), *(jt)); } } inline void toPCL(const pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert) { pcl_vert.vertices = vert.vertices; } inline void toPCL(const std::vector &verts, std::vector &pcl_verts) { pcl_verts.resize(verts.size()); std::vector::const_iterator it = verts.begin(); std::vector::iterator jt = pcl_verts.begin(); for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) { toPCL(*(it), *(jt)); } } inline void moveToPCL(pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert) { pcl_vert.vertices.swap(vert.vertices); } inline void moveToPCL(std::vector &verts, std::vector &pcl_verts) { pcl_verts.resize(verts.size()); std::vector::iterator it = verts.begin(); std::vector::iterator jt = pcl_verts.begin(); for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) { moveToPCL(*(it), *(jt)); } } /** pcl::PolygonMesh <=> pcl_msgs::PolygonMesh **/ inline void fromPCL(const pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh) { fromPCL(pcl_mesh.header, mesh.header); fromPCL(pcl_mesh.cloud, mesh.cloud); fromPCL(pcl_mesh.polygons, mesh.polygons); } inline void moveFromPCL(pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh) { fromPCL(pcl_mesh.header, mesh.header); moveFromPCL(pcl_mesh.cloud, mesh.cloud); moveFromPCL(pcl_mesh.cloud, mesh.cloud); } inline void toPCL(const pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh) { toPCL(mesh.header, pcl_mesh.header); toPCL(mesh.cloud, pcl_mesh.cloud); toPCL(mesh.polygons, pcl_mesh.polygons); } inline void moveToPCL(pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh) { toPCL(mesh.header, pcl_mesh.header); moveToPCL(mesh.cloud, pcl_mesh.cloud); moveToPCL(mesh.polygons, pcl_mesh.polygons); } } // namespace pcl_conversions namespace pcl { /** Overload pcl::getFieldIndex **/ inline int getFieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) { // Get the index we need for (size_t d = 0; d < cloud.fields.size(); ++d) { if (cloud.fields[d].name == field_name) { return (static_cast(d)); } } return (-1); } /** Overload pcl::getFieldsList **/ inline std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud) { std::string result; for (size_t i = 0; i < cloud.fields.size () - 1; ++i) { result += cloud.fields[i].name + " "; } result += cloud.fields[cloud.fields.size () - 1].name; return (result); } /** Provide pcl::toROSMsg **/ inline void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image) { pcl::PCLPointCloud2 pcl_cloud; pcl_conversions::toPCL(cloud, pcl_cloud); pcl::PCLImage pcl_image; pcl::toPCLPointCloud2(pcl_cloud, pcl_image); pcl_conversions::moveFromPCL(pcl_image, image); } inline void moveToROSMsg(sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image) { pcl::PCLPointCloud2 pcl_cloud; pcl_conversions::moveToPCL(cloud, pcl_cloud); pcl::PCLImage pcl_image; pcl::toPCLPointCloud2(pcl_cloud, pcl_image); pcl_conversions::moveFromPCL(pcl_image, image); } /** Overload pcl::createMapping **/ template void createMapping(const std::vector& msg_fields, MsgFieldMap& field_map) { std::vector pcl_msg_fields; pcl_conversions::toPCL(msg_fields, pcl_msg_fields); return createMapping(pcl_msg_fields, field_map); } namespace io { /** Overload pcl::io::savePCDFile **/ inline int savePCDFile(const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), const bool binary_mode = false) { pcl::PCLPointCloud2 pcl_cloud; pcl_conversions::toPCL(cloud, pcl_cloud); return pcl::io::savePCDFile(file_name, pcl_cloud, origin, orientation, binary_mode); } inline int destructiveSavePCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), const bool binary_mode = false) { pcl::PCLPointCloud2 pcl_cloud; pcl_conversions::moveToPCL(cloud, pcl_cloud); return pcl::io::savePCDFile(file_name, pcl_cloud, origin, orientation, binary_mode); } /** Overload pcl::io::loadPCDFile **/ inline int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud) { pcl::PCLPointCloud2 pcl_cloud; int ret = pcl::io::loadPCDFile(file_name, pcl_cloud); pcl_conversions::moveFromPCL(pcl_cloud, cloud); return ret; } } // namespace io /** Overload asdf **/ inline bool concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out) { //if one input cloud has no points, but the other input does, just return the cloud with points if (cloud1.width * cloud1.height == 0 && cloud2.width * cloud2.height > 0) { cloud_out = cloud2; return (true); } else if (cloud1.width*cloud1.height > 0 && cloud2.width*cloud2.height == 0) { cloud_out = cloud1; return (true); } bool strip = false; for (size_t i = 0; i < cloud1.fields.size (); ++i) if (cloud1.fields[i].name == "_") strip = true; for (size_t i = 0; i < cloud2.fields.size (); ++i) if (cloud2.fields[i].name == "_") strip = true; if (!strip && cloud1.fields.size () != cloud2.fields.size ()) { PCL_ERROR ("[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.fields.size (), cloud2.fields.size ()); return (false); } // Copy cloud1 into cloud_out cloud_out = cloud1; size_t nrpts = cloud_out.data.size (); // Height = 1 => no more organized cloud_out.width = cloud1.width * cloud1.height + cloud2.width * cloud2.height; cloud_out.height = 1; if (!cloud1.is_dense || !cloud2.is_dense) cloud_out.is_dense = false; else cloud_out.is_dense = true; // We need to strip the extra padding fields if (strip) { // Get the field sizes for the second cloud std::vector fields2; std::vector fields2_sizes; for (size_t j = 0; j < cloud2.fields.size (); ++j) { if (cloud2.fields[j].name == "_") continue; fields2_sizes.push_back (cloud2.fields[j].count * pcl::getFieldSize (cloud2.fields[j].datatype)); fields2.push_back (cloud2.fields[j]); } cloud_out.data.resize (nrpts + (cloud2.width * cloud2.height) * cloud_out.point_step); // Copy the second cloud for (size_t cp = 0; cp < cloud2.width * cloud2.height; ++cp) { int i = 0; for (size_t j = 0; j < fields2.size (); ++j) { if (cloud1.fields[i].name == "_") { ++i; continue; } // We're fine with the special RGB vs RGBA use case if ((cloud1.fields[i].name == "rgb" && fields2[j].name == "rgba") || (cloud1.fields[i].name == "rgba" && fields2[j].name == "rgb") || (cloud1.fields[i].name == fields2[j].name)) { memcpy (reinterpret_cast (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]), reinterpret_cast (&cloud2.data[cp * cloud2.point_step + cloud2.fields[j].offset]), fields2_sizes[j]); ++i; // increment the field size i } } } } else { for (size_t i = 0; i < cloud1.fields.size (); ++i) { // We're fine with the special RGB vs RGBA use case if ((cloud1.fields[i].name == "rgb" && cloud2.fields[i].name == "rgba") || (cloud1.fields[i].name == "rgba" && cloud2.fields[i].name == "rgb")) continue; // Otherwise we need to make sure the names are the same if (cloud1.fields[i].name != cloud2.fields[i].name) { 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 ()); return (false); } } cloud_out.data.resize (nrpts + cloud2.data.size ()); memcpy (&cloud_out.data[nrpts], &cloud2.data[0], cloud2.data.size ()); } return (true); } } // namespace pcl namespace ros { template<> struct DefaultMessageCreator { boost::shared_ptr operator() () { boost::shared_ptr msg(new pcl::PCLPointCloud2()); return msg; } }; namespace message_traits { template<> struct MD5Sum { static const char* value() { return MD5Sum::value(); } static const char* value(const pcl::PCLPointCloud2&) { return value(); } static const uint64_t static_value1 = MD5Sum::static_value1; static const uint64_t static_value2 = MD5Sum::static_value2; // If the definition of sensor_msgs/PointCloud2 changes, we'll get a compile error here. ROS_STATIC_ASSERT(static_value1 == 0x1158d486dd51d683ULL); ROS_STATIC_ASSERT(static_value2 == 0xce2f1be655c3c181ULL); }; template<> struct DataType { static const char* value() { return DataType::value(); } static const char* value(const pcl::PCLPointCloud2&) { return value(); } }; template<> struct Definition { static const char* value() { return Definition::value(); } static const char* value(const pcl::PCLPointCloud2&) { return value(); } }; template<> struct HasHeader : TrueType {}; } // namespace ros::message_traits namespace serialization { /* * Provide a custom serialization for pcl::PCLPointCloud2 */ template<> struct Serializer { template inline static void write(Stream& stream, const pcl::PCLPointCloud2& m) { std_msgs::Header header; pcl_conversions::fromPCL(m.header, header); stream.next(header); stream.next(m.height); stream.next(m.width); std::vector pfs; pcl_conversions::fromPCL(m.fields, pfs); stream.next(pfs); stream.next(m.is_bigendian); stream.next(m.point_step); stream.next(m.row_step); stream.next(m.data); stream.next(m.is_dense); } template inline static void read(Stream& stream, pcl::PCLPointCloud2& m) { std_msgs::Header header; stream.next(header); pcl_conversions::toPCL(header, m.header); stream.next(m.height); stream.next(m.width); std::vector pfs; stream.next(pfs); pcl_conversions::toPCL(pfs, m.fields); stream.next(m.is_bigendian); stream.next(m.point_step); stream.next(m.row_step); stream.next(m.data); stream.next(m.is_dense); } inline static uint32_t serializedLength(const pcl::PCLPointCloud2& m) { uint32_t length = 0; std_msgs::Header header; pcl_conversions::fromPCL(m.header, header); length += serializationLength(header); length += 4; // height length += 4; // width std::vector pfs; pcl_conversions::fromPCL(m.fields, pfs); length += serializationLength(pfs); // fields length += 1; // is_bigendian length += 4; // point_step length += 4; // row_step length += 4; // data's size length += m.data.size() * sizeof(pcl::uint8_t); length += 1; // is_dense return length; } }; /* * Provide a custom serialization for pcl::PCLPointField */ template<> struct Serializer { template inline static void write(Stream& stream, const pcl::PCLPointField& m) { stream.next(m.name); stream.next(m.offset); stream.next(m.datatype); stream.next(m.count); } template inline static void read(Stream& stream, pcl::PCLPointField& m) { stream.next(m.name); stream.next(m.offset); stream.next(m.datatype); stream.next(m.count); } inline static uint32_t serializedLength(const pcl::PCLPointField& m) { uint32_t length = 0; length += serializationLength(m.name); length += serializationLength(m.offset); length += serializationLength(m.datatype); length += serializationLength(m.count); return length; } }; /* * Provide a custom serialization for pcl::PCLHeader */ template<> struct Serializer { template inline static void write(Stream& stream, const pcl::PCLHeader& m) { std_msgs::Header header; pcl_conversions::fromPCL(m, header); stream.next(header); } template inline static void read(Stream& stream, pcl::PCLHeader& m) { std_msgs::Header header; stream.next(header); pcl_conversions::toPCL(header, m); } inline static uint32_t serializedLength(const pcl::PCLHeader& m) { uint32_t length = 0; std_msgs::Header header; pcl_conversions::fromPCL(m, header); length += serializationLength(header); return length; } }; } // namespace ros::serialization } // namespace ros #endif /* PCL_CONVERSIONS_H__ */