37 #ifndef PCL_CONVERSIONS_H__ 
   38 #define PCL_CONVERSIONS_H__ 
   44 #include <pcl/conversions.h> 
   46 #include <pcl/PCLHeader.h> 
   47 #include <std_msgs/Header.h> 
   49 #include <pcl/PCLImage.h> 
   50 #include <sensor_msgs/Image.h> 
   52 #include <pcl/PCLPointField.h> 
   53 #include <sensor_msgs/PointField.h> 
   55 #include <pcl/PCLPointCloud2.h> 
   56 #include <sensor_msgs/PointCloud2.h> 
   58 #include <pcl/PointIndices.h> 
   59 #include <pcl_msgs/PointIndices.h> 
   61 #include <pcl/ModelCoefficients.h> 
   62 #include <pcl_msgs/ModelCoefficients.h> 
   64 #include <pcl/Vertices.h> 
   65 #include <pcl_msgs/Vertices.h> 
   67 #include <pcl/PolygonMesh.h> 
   68 #include <pcl_msgs/PolygonMesh.h> 
   70 #include <pcl/io/pcd_io.h> 
   72 #include <Eigen/StdVector> 
   73 #include <Eigen/Geometry> 
   88     pcl_stamp = stamp.
toNSec() / 1000ull;  
 
  102     std::uint64_t pcl_stamp;
 
  103     toPCL(stamp, pcl_stamp);
 
  110   void fromPCL(
const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
 
  113     header.seq = pcl_header.seq;
 
  114     header.frame_id = pcl_header.frame_id;
 
  118   void toPCL(
const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
 
  121     pcl_header.seq = 
header.seq;
 
  122     pcl_header.frame_id = 
header.frame_id;
 
  126   std_msgs::Header 
fromPCL(
const pcl::PCLHeader &pcl_header)
 
  134   pcl::PCLHeader 
toPCL(
const std_msgs::Header &header)
 
  136     pcl::PCLHeader pcl_header;
 
  146     fromPCL(pcl_image.header, image.header);
 
  147     image.height = pcl_image.height;
 
  148     image.width = pcl_image.width;
 
  149     image.encoding = pcl_image.encoding;
 
  150     image.is_bigendian = pcl_image.is_bigendian;
 
  151     image.step = pcl_image.step;
 
  155   void fromPCL(
const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
 
  158     image.data = pcl_image.data;
 
  162   void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
 
  165     image.data.swap(pcl_image.data);
 
  171     toPCL(image.header, pcl_image.header);
 
  172     pcl_image.height = image.height;
 
  173     pcl_image.width = image.width;
 
  174     pcl_image.encoding = image.encoding;
 
  175     pcl_image.is_bigendian = image.is_bigendian;
 
  176     pcl_image.step = image.step;
 
  180   void toPCL(
const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
 
  183     pcl_image.data = image.data;
 
  187   void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
 
  190     pcl_image.data.swap(image.data);
 
  196   void fromPCL(
const pcl::PCLPointField &pcl_pf, sensor_msgs::PointField &pf)
 
  198     pf.name = pcl_pf.name;
 
  199     pf.offset = pcl_pf.offset;
 
  200     pf.datatype = pcl_pf.datatype;
 
  201     pf.count = pcl_pf.count;
 
  205   void fromPCL(
const std::vector<pcl::PCLPointField> &pcl_pfs, std::vector<sensor_msgs::PointField> &pfs)
 
  207     pfs.resize(pcl_pfs.size());
 
  208     std::vector<pcl::PCLPointField>::const_iterator it = pcl_pfs.begin();
 
  210     for(; it != pcl_pfs.end(); ++it, ++i) {
 
  213     std::sort(pfs.begin(), pfs.end(), [](
const auto& field_a, 
const auto& field_b)
 
  215                                         return field_a.offset < field_b.offset;
 
  220   void toPCL(
const sensor_msgs::PointField &pf, pcl::PCLPointField &pcl_pf)
 
  222     pcl_pf.name = pf.name;
 
  223     pcl_pf.offset = pf.offset;
 
  224     pcl_pf.datatype = pf.datatype;
 
  225     pcl_pf.count = pf.count;
 
  229   void toPCL(
const std::vector<sensor_msgs::PointField> &pfs, std::vector<pcl::PCLPointField> &pcl_pfs)
 
  231     pcl_pfs.resize(pfs.size());
 
  232     std::vector<sensor_msgs::PointField>::const_iterator it = pfs.begin();
 
  234     for(; it != pfs.end(); ++it, ++i) {
 
  235       toPCL(*(it), pcl_pfs[i]);
 
  244     fromPCL(pcl_pc2.header, pc2.header);
 
  245     pc2.height = pcl_pc2.height;
 
  246     pc2.width = pcl_pc2.width;
 
  247     fromPCL(pcl_pc2.fields, pc2.fields);
 
  248     pc2.is_bigendian = pcl_pc2.is_bigendian;
 
  249     pc2.point_step = pcl_pc2.point_step;
 
  250     pc2.row_step = pcl_pc2.row_step;
 
  251     pc2.is_dense = pcl_pc2.is_dense;
 
  255   void fromPCL(
const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
 
  258     pc2.data = pcl_pc2.data;
 
  262   void moveFromPCL(pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
 
  265     pc2.data.swap(pcl_pc2.data);
 
  271     toPCL(pc2.header, pcl_pc2.header);
 
  272     pcl_pc2.height = pc2.height;
 
  273     pcl_pc2.width = pc2.width;
 
  274     toPCL(pc2.fields, pcl_pc2.fields);
 
  275     pcl_pc2.is_bigendian = pc2.is_bigendian;
 
  276     pcl_pc2.point_step = pc2.point_step;
 
  277     pcl_pc2.row_step = pc2.row_step;
 
  278     pcl_pc2.is_dense = pc2.is_dense;
 
  282   void toPCL(
const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
 
  285     pcl_pc2.data = pc2.data;
 
  289   void moveToPCL(sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
 
  292     pcl_pc2.data.swap(pc2.data);
 
  298   void fromPCL(
const pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
 
  300     fromPCL(pcl_pi.header, pi.header);
 
  301     pi.indices = pcl_pi.indices;
 
  305   void moveFromPCL(pcl::PointIndices &pcl_pi, pcl_msgs::PointIndices &pi)
 
  307     fromPCL(pcl_pi.header, pi.header);
 
  308     pi.indices.swap(pcl_pi.indices);
 
  312   void toPCL(
const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
 
  314     toPCL(pi.header, pcl_pi.header);
 
  315     pcl_pi.indices = pi.indices;
 
  319   void moveToPCL(pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
 
  321     toPCL(pi.header, pcl_pi.header);
 
  322     pcl_pi.indices.swap(pi.indices);
 
  328   void fromPCL(
const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
 
  330     fromPCL(pcl_mc.header, mc.header);
 
  331     mc.values = pcl_mc.values;
 
  335   void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
 
  337     fromPCL(pcl_mc.header, mc.header);
 
  338     mc.values.swap(pcl_mc.values);
 
  342   void toPCL(
const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
 
  344     toPCL(mc.header, pcl_mc.header);
 
  345     pcl_mc.values = mc.values;
 
  349   void moveToPCL(pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
 
  351     toPCL(mc.header, pcl_mc.header);
 
  352     pcl_mc.values.swap(mc.values);
 
  360     inline void move(std::vector<T> &a, std::vector<T> &b)
 
  365     template <
class T1, 
class T2>
 
  366     inline void move(std::vector<T1> &a, std::vector<T2> &b)
 
  368       b.assign(a.cbegin(), a.cend());
 
  373   void fromPCL(
const pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
 
  375     vert.vertices.assign(pcl_vert.vertices.cbegin(), pcl_vert.vertices.cend());
 
  379   void fromPCL(
const std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
 
  381     verts.resize(pcl_verts.size());
 
  382     std::vector<pcl::Vertices>::const_iterator it = pcl_verts.begin();
 
  383     std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
 
  384     for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
 
  390   void moveFromPCL(pcl::Vertices &pcl_vert, pcl_msgs::Vertices &vert)
 
  396   void fromPCL(std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
 
  398     verts.resize(pcl_verts.size());
 
  399     std::vector<pcl::Vertices>::iterator it = pcl_verts.begin();
 
  400     std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
 
  401     for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
 
  407   void toPCL(
const pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
 
  409     pcl_vert.vertices.assign(vert.vertices.cbegin(), vert.vertices.cend());
 
  413   void toPCL(
const std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
 
  415     pcl_verts.resize(verts.size());
 
  416     std::vector<pcl_msgs::Vertices>::const_iterator it = verts.begin();
 
  417     std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
 
  418     for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
 
  424   void moveToPCL(pcl_msgs::Vertices &vert, pcl::Vertices &pcl_vert)
 
  430   void moveToPCL(std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
 
  432     pcl_verts.resize(verts.size());
 
  433     std::vector<pcl_msgs::Vertices>::iterator it = verts.begin();
 
  434     std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
 
  435     for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
 
  443   void fromPCL(
const pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
 
  445     fromPCL(pcl_mesh.header, mesh.header);
 
  446     fromPCL(pcl_mesh.cloud, mesh.cloud);
 
  447     fromPCL(pcl_mesh.polygons, mesh.polygons);
 
  451   void moveFromPCL(pcl::PolygonMesh &pcl_mesh, pcl_msgs::PolygonMesh &mesh)
 
  453     fromPCL(pcl_mesh.header, mesh.header);
 
  458   void toPCL(
const pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
 
  460     toPCL(mesh.header, pcl_mesh.header);
 
  461     toPCL(mesh.cloud, pcl_mesh.cloud);
 
  462     toPCL(mesh.polygons, pcl_mesh.polygons);
 
  466   void moveToPCL(pcl_msgs::PolygonMesh &mesh, pcl::PolygonMesh &pcl_mesh)
 
  468     toPCL(mesh.header, pcl_mesh.header);
 
  470     moveToPCL(mesh.polygons, pcl_mesh.polygons);
 
  479   inline int getFieldIndex(
const sensor_msgs::PointCloud2 &cloud, 
const std::string &field_name)
 
  482     for (
size_t d = 0; 
d < cloud.fields.size(); ++
d) {
 
  483       if (cloud.fields[
d].name == field_name) {
 
  484         return (
static_cast<int>(
d));
 
  495     for (
size_t i = 0; i < cloud.fields.size () - 1; ++i) {
 
  496       result += cloud.fields[i].name + 
" ";
 
  498     result += cloud.fields[cloud.fields.size () - 1].name;
 
  505   void toROSMsg(
const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
 
  507     pcl::PCLPointCloud2 pcl_cloud;
 
  509     pcl::PCLImage pcl_image;
 
  510     pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
 
  515   void moveToROSMsg(sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
 
  517     pcl::PCLPointCloud2 pcl_cloud;
 
  519     pcl::PCLImage pcl_image;
 
  520     pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
 
  524   template<
typename T> 
void 
  525   toROSMsg (
const pcl::PointCloud<T> &cloud, sensor_msgs::Image& msg)
 
  528     if (cloud.width == 0 && cloud.height == 0)
 
  530       throw std::runtime_error(
"Needs to be a dense like cloud!!");
 
  534       if (cloud.points.size () != cloud.width * cloud.height)
 
  535         throw std::runtime_error(
"The width and height do not match the cloud size!");
 
  536       msg.height = cloud.height;
 
  537       msg.width = cloud.width;
 
  541     msg.encoding = 
"bgr8";
 
  542     msg.step = msg.width * 
sizeof (std::uint8_t) * 3;
 
  543     msg.data.resize (msg.step * msg.height);
 
  544     for (
size_t y = 0; y < cloud.height; y++)
 
  546       for (
size_t x = 0; x < cloud.width; x++)
 
  548         std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
 
  549         memcpy (pixel, &cloud (x, y).rgb, 3 * 
sizeof(std::uint8_t));
 
  557   void toROSMsg(
const pcl::PointCloud<T> &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
 
  559     pcl::PCLPointCloud2 pcl_pc2;
 
  560 #if PCL_VERSION_COMPARE(>=, 1, 14, 1) 
  562     pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2, 
false);
 
  564     pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
 
  570   void fromROSMsg(
const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
 
  572     pcl::PCLPointCloud2 pcl_pc2;
 
  573 #if PCL_VERSION_COMPARE(>=, 1, 13, 1) 
  575     pcl::MsgFieldMap field_map;
 
  576     pcl::createMapping<T> (pcl_pc2.fields, field_map);
 
  577     pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud, field_map, &cloud.data[0]);
 
  580     pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
 
  585   void moveFromROSMsg(sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
 
  587     pcl::PCLPointCloud2 pcl_pc2;
 
  589     pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
 
  594   template<
typename Po
intT>
 
  595   void createMapping(
const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
 
  597     std::vector<pcl::PCLPointField> pcl_msg_fields;
 
  599     return createMapping<PointT>(pcl_msg_fields, field_map);
 
  607     savePCDFile(
const std::string &file_name, 
const sensor_msgs::PointCloud2 &cloud,
 
  608                 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
 
  609                 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
 
  610                 const bool binary_mode = 
false)
 
  612       pcl::PCLPointCloud2 pcl_cloud;
 
  619                            const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
 
  620                            const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
 
  621                            const bool binary_mode = 
false)
 
  623       pcl::PCLPointCloud2 pcl_cloud;
 
  630     inline int loadPCDFile(
const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
 
  632       pcl::PCLPointCloud2 pcl_cloud;
 
  644                               const sensor_msgs::PointCloud2 &cloud2,
 
  645                               sensor_msgs::PointCloud2 &cloud_out)
 
  648     if (cloud1.width * cloud1.height == 0 && cloud2.width * cloud2.height > 0)
 
  653     else if (cloud1.width*cloud1.height > 0 && cloud2.width*cloud2.height == 0)
 
  660     for (
size_t i = 0; i < cloud1.fields.size (); ++i)
 
  661       if (cloud1.fields[i].name == 
"_")
 
  664     for (
size_t i = 0; i < cloud2.fields.size (); ++i)
 
  665       if (cloud2.fields[i].name == 
"_")
 
  668     if (!strip && cloud1.fields.size () != cloud2.fields.size ())
 
  670       PCL_ERROR (
"[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.fields.size (), cloud2.fields.size ());
 
  676     size_t nrpts = cloud_out.data.size ();
 
  678     cloud_out.width    = cloud1.width * cloud1.height + cloud2.width * cloud2.height;
 
  679     cloud_out.height   = 1;
 
  680     if (!cloud1.is_dense || !cloud2.is_dense)
 
  681       cloud_out.is_dense = 
false;
 
  683       cloud_out.is_dense = 
true;
 
  689       std::vector<sensor_msgs::PointField> fields2;
 
  690       std::vector<int> fields2_sizes;
 
  691       for (
size_t j = 0; j < cloud2.fields.size (); ++j)
 
  693         if (cloud2.fields[j].name == 
"_")
 
  696         fields2_sizes.push_back (cloud2.fields[j].count *
 
  697                                  pcl::getFieldSize (cloud2.fields[j].datatype));
 
  698         fields2.push_back (cloud2.fields[j]);
 
  701       cloud_out.data.resize (nrpts + (cloud2.width * cloud2.height) * cloud_out.point_step);
 
  704       for (
size_t cp = 0; cp < cloud2.width * cloud2.height; ++cp)
 
  707         for (
size_t j = 0; j < fields2.size (); ++j)
 
  709           if (cloud1.fields[i].name == 
"_")
 
  716           if ((cloud1.fields[i].name == 
"rgb" && fields2[j].name == 
"rgba") ||
 
  717               (cloud1.fields[i].name == 
"rgba" && fields2[j].name == 
"rgb") ||
 
  718               (cloud1.fields[i].name == fields2[j].name))
 
  720             memcpy (
reinterpret_cast<char*
> (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]),
 
  721                     reinterpret_cast<const char*
> (&cloud2.data[cp * cloud2.point_step + cloud2.fields[j].offset]),
 
  730       for (
size_t i = 0; i < cloud1.fields.size (); ++i)
 
  733         if ((cloud1.fields[i].name == 
"rgb" && cloud2.fields[i].name == 
"rgba") ||
 
  734             (cloud1.fields[i].name == 
"rgba" && cloud2.fields[i].name == 
"rgb"))
 
  737         if (cloud1.fields[i].name != cloud2.fields[i].name)
 
  739           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 ());
 
  743       cloud_out.data.resize (nrpts + cloud2.data.size ());
 
  744       memcpy (&cloud_out.data[nrpts], &cloud2.data[0], cloud2.data.size ());
 
  763   namespace message_traits
 
  769       static const char* 
value(
const pcl::PCLPointCloud2&) { 
return value(); }
 
  783       static const char* 
value(
const pcl::PCLPointCloud2&) { 
return value(); }
 
  790       static const char* 
value(
const pcl::PCLPointCloud2&) { 
return value(); }
 
  796   namespace serialization
 
  804       template<
typename Stream>
 
  805       inline static void write(
Stream& stream, 
const pcl::PCLPointCloud2& m)
 
  810         stream.next(m.height);
 
  811         stream.next(m.width);
 
  812         std::vector<sensor_msgs::PointField> pfs;
 
  815         stream.next(m.is_bigendian);
 
  816         stream.next(m.point_step);
 
  817         stream.next(m.row_step);
 
  819         stream.next(m.is_dense);
 
  822       template<
typename Stream>
 
  823       inline static void read(
Stream& stream, pcl::PCLPointCloud2& m)
 
  828         stream.next(m.height);
 
  829         stream.next(m.width);
 
  830         std::vector<sensor_msgs::PointField> pfs;
 
  833         stream.next(m.is_bigendian);
 
  834         stream.next(m.point_step);
 
  835         stream.next(m.row_step);
 
  837         stream.next(m.is_dense);
 
  849         std::vector<sensor_msgs::PointField> pfs;
 
  856         length += m.data.size() * 
sizeof(std::uint8_t);
 
  869       template<
typename Stream>
 
  870       inline static void write(
Stream& stream, 
const pcl::PCLPointField& m)
 
  873         stream.next(m.offset);
 
  874         stream.next(m.datatype);
 
  875         stream.next(m.count);
 
  878       template<
typename Stream>
 
  879       inline static void read(
Stream& stream, pcl::PCLPointField& m)
 
  882         stream.next(m.offset);
 
  883         stream.next(m.datatype);
 
  884         stream.next(m.count);
 
  906       template<
typename Stream>
 
  914       template<
typename Stream>