[pcl-conversions] 01/01: Imported Upstream version 0.2.1

Jochen Sprickerhof jspricke-guest at moszumanska.debian.org
Tue Aug 4 16:13:12 UTC 2015


This is an automated email from the git hooks/post-receive script.

jspricke-guest pushed a commit to annotated tag upstream/0.2.1
in repository pcl-conversions.

commit a956490956225261953b3e25aac3a12f8de6875c
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Tue Aug 4 17:24:30 2015 +0200

    Imported Upstream version 0.2.1
---
 .gitignore                                |   2 +
 CHANGELOG.rst                             |  48 ++
 CMakeLists.txt                            |  27 +
 README.rst                                |  22 +
 include/pcl_conversions/pcl_conversions.h | 908 ++++++++++++++++++++++++++++++
 package.xml                               |  33 ++
 test/test_pcl_conversions.cpp             | 154 +++++
 7 files changed, 1194 insertions(+)

diff --git a/.gitignore b/.gitignore
new file mode 100644
index 0000000..d0adf26
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,2 @@
+build
+*.sublime-*
diff --git a/CHANGELOG.rst b/CHANGELOG.rst
new file mode 100644
index 0000000..1bce5a4
--- /dev/null
+++ b/CHANGELOG.rst
@@ -0,0 +1,48 @@
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+Changelog for package pcl_conversions
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+0.2.1 (2015-06-08)
+------------------
+* Added a test for rounding errors in stamp conversion
+  for some values the test fails.
+* add pcl::PointCloud to Image msg converter for extracting the rgb component of a cloud
+* Contributors: Brice Rebsamen, Lucid One, Michael Ferguson, Paul Bovbel
+
+0.2.0 (2014-04-10)
+------------------
+* Added conversions for stamp types
+* update maintainer info, add eigen dependency
+* fix Eigen dependency
+* Make pcl_conversions run_depend on libpcl-all-dev
+* Contributors: Brice Rebsamen, Paul Bovbel, Scott K Logan, William Woodall
+
+0.1.5 (2013-08-27)
+------------------
+* Use new pcl rosdep keys (libpcl-all and libpcl-all-dev)
+
+0.1.4 (2013-07-13)
+------------------
+* Fixup dependencies and CMakeLists.txt:
+
+  * Added a versioned dependency on pcl, fixes `#1 <https://github.com/ros-perception/pcl_conversions/issues/1>`_
+  * Added a dependency on pcl_msgs, fixes `#2 <https://github.com/ros-perception/pcl_conversions/issues/2>`_
+  * Wrapped the test target in a CATKIN_ENABLE_TESTING check
+
+0.1.3 (2013-07-13)
+------------------
+* Add missing dependency on roscpp
+* Fixup tests and pcl usage in CMakeList.txt
+
+0.1.2 (2013-07-12)
+------------------
+* small fix for conversion functions
+
+0.1.1 (2013-07-10)
+------------------
+* Fix find_package bug with pcl
+
+0.1.0 (2013-07-09 21:49:26 -0700)
+---------------------------------
+- Initial release
+- This package is designed to allow users to more easily convert between pcl-1.7+ types and ROS message types
diff --git a/CMakeLists.txt b/CMakeLists.txt
new file mode 100644
index 0000000..5538c47
--- /dev/null
+++ b/CMakeLists.txt
@@ -0,0 +1,27 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(pcl_conversions)
+
+find_package(catkin REQUIRED COMPONENTS pcl_msgs roscpp sensor_msgs std_msgs cmake_modules)
+
+find_package(PCL REQUIRED QUIET COMPONENTS common)
+find_package(Eigen REQUIRED)
+
+include_directories(include ${catkin_INCLUDE_DIRS} ${PCL_COMMON_INCLUDE_DIRS} ${Eigen_INCLUDE_DIRS})
+
+catkin_package(
+  INCLUDE_DIRS include ${PCL_COMMON_INCLUDE_DIRS}
+  CATKIN_DEPENDS pcl_msgs roscpp sensor_msgs std_msgs
+)
+
+# Mark cpp header files for installation
+install(DIRECTORY include/${PROJECT_NAME}/
+  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+  FILES_MATCHING PATTERN "*.h"
+  PATTERN ".svn" EXCLUDE
+)
+
+# Add gtest based cpp test target
+if(CATKIN_ENABLE_TESTING)
+  catkin_add_gtest(${PROJECT_NAME}-test test/test_pcl_conversions.cpp)
+  target_link_libraries(${PROJECT_NAME}-test ${catkin_LIBRARIES})
+endif()
diff --git a/README.rst b/README.rst
new file mode 100644
index 0000000..4ec7b6a
--- /dev/null
+++ b/README.rst
@@ -0,0 +1,22 @@
+pcl_conversions
+===============
+
+This package provides conversions from PCL data types and ROS message types.
+
+
+Code & tickets
+--------------
+
+.. Build status: |Build Status|
+
+.. .. |Build Status| image:: https://secure.travis-ci.org/ros-perception/pcl_conversions.png
+   :target: http://travis-ci.org/ros-perception/pcl_conversions
+
++-----------------+------------------------------------------------------------+
+| pcl_conversions | http://ros.org/wiki/pcl_conversions                        |
++-----------------+------------------------------------------------------------+
+| Issues          | http://github.com/ros-perception/pcl_conversions/issues    |
++-----------------+------------------------------------------------------------+
+.. | Documentation   | http://ros-perception.github.com/pcl_conversions/doc       |
+.. +-----------------+------------------------------------------------------------+
+
diff --git a/include/pcl_conversions/pcl_conversions.h b/include/pcl_conversions/pcl_conversions.h
new file mode 100644
index 0000000..44c4381
--- /dev/null
+++ b/include/pcl_conversions/pcl_conversions.h
@@ -0,0 +1,908 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2013, Open Source Robotics Foundation, Inc.
+ * Copyright (c) 2010-2012, Willow Garage, 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 <vector>
+
+#include <ros/ros.h>
+
+#include <pcl/conversions.h>
+
+#include <pcl/PCLHeader.h>
+#include <std_msgs/Header.h>
+
+#include <pcl/PCLImage.h>
+#include <sensor_msgs/Image.h>
+
+#include <pcl/PCLPointField.h>
+#include <sensor_msgs/PointField.h>
+
+#include <pcl/PCLPointCloud2.h>
+#include <sensor_msgs/PointCloud2.h>
+
+#include <pcl/PointIndices.h>
+#include <pcl_msgs/PointIndices.h>
+
+#include <pcl/ModelCoefficients.h>
+#include <pcl_msgs/ModelCoefficients.h>
+
+#include <pcl/Vertices.h>
+#include <pcl_msgs/Vertices.h>
+
+#include <pcl/PolygonMesh.h>
+#include <pcl_msgs/PolygonMesh.h>
+
+#include <pcl/io/pcd_io.h>
+
+#include <Eigen/StdVector>
+#include <Eigen/Geometry>
+
+namespace pcl_conversions {
+
+  /** PCLHeader <=> Header **/
+
+  inline
+  void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
+  {
+    stamp.fromNSec(pcl_stamp * 1000ull);  // Convert from us to ns
+  }
+
+  inline
+  void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
+  {
+    pcl_stamp = stamp.toNSec() / 1000ull;  // Convert from ns to us
+  }
+
+  inline
+  ros::Time fromPCL(const pcl::uint64_t &pcl_stamp)
+  {
+    ros::Time stamp;
+    fromPCL(pcl_stamp, stamp);
+    return stamp;
+  }
+
+  inline
+  pcl::uint64_t toPCL(const ros::Time &stamp)
+  {
+    pcl::uint64_t pcl_stamp;
+    toPCL(stamp, pcl_stamp);
+    return pcl_stamp;
+  }
+
+  /** PCLHeader <=> Header **/
+
+  inline
+  void fromPCL(const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
+  {
+    fromPCL(pcl_header.stamp, header.stamp);
+    header.seq = pcl_header.seq;
+    header.frame_id = pcl_header.frame_id;
+  }
+
+  inline
+  void toPCL(const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
+  {
+    toPCL(header.stamp, pcl_header.stamp);
+    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::PCLPointField> &pcl_pfs, std::vector<sensor_msgs::PointField> &pfs)
+  {
+    pfs.resize(pcl_pfs.size());
+    std::vector<pcl::PCLPointField>::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<sensor_msgs::PointField> &pfs, std::vector<pcl::PCLPointField> &pcl_pfs)
+  {
+    pcl_pfs.resize(pfs.size());
+    std::vector<sensor_msgs::PointField>::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::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
+  {
+    verts.resize(pcl_verts.size());
+    std::vector<pcl::Vertices>::const_iterator it = pcl_verts.begin();
+    std::vector<pcl_msgs::Vertices>::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::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
+  {
+    verts.resize(pcl_verts.size());
+    std::vector<pcl::Vertices>::iterator it = pcl_verts.begin();
+    std::vector<pcl_msgs::Vertices>::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<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
+  {
+    pcl_verts.resize(verts.size());
+    std::vector<pcl_msgs::Vertices>::const_iterator it = verts.begin();
+    std::vector<pcl::Vertices>::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<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
+  {
+    pcl_verts.resize(verts.size());
+    std::vector<pcl_msgs::Vertices>::iterator it = verts.begin();
+    std::vector<pcl::Vertices>::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<int>(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);
+  }
+
+  template<typename T> void
+  toROSMsg (const pcl::PointCloud<T> &cloud, sensor_msgs::Image& msg)
+  {
+    // Ease the user's burden on specifying width/height for unorganized datasets
+    if (cloud.width == 0 && cloud.height == 0)
+    {
+      throw std::runtime_error("Needs to be a dense like cloud!!");
+    }
+    else
+    {
+      if (cloud.points.size () != cloud.width * cloud.height)
+        throw std::runtime_error("The width and height do not match the cloud size!");
+      msg.height = cloud.height;
+      msg.width = cloud.width;
+    }
+
+    // sensor_msgs::image_encodings::BGR8;
+    msg.encoding = "bgr8";
+    msg.step = msg.width * sizeof (uint8_t) * 3;
+    msg.data.resize (msg.step * msg.height);
+    for (size_t y = 0; y < cloud.height; y++)
+    {
+      for (size_t x = 0; x < cloud.width; x++)
+      {
+        uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
+        memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t));
+      }
+    }
+  }
+
+  /** Provide to/fromROSMsg for sensor_msgs::PointCloud2 <=> pcl::PointCloud<T> **/
+
+  template<typename T>
+  void toROSMsg(const pcl::PointCloud<T> &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
+  {
+    pcl::PCLPointCloud2 pcl_pc2;
+    pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
+    pcl_conversions::moveFromPCL(pcl_pc2, cloud);
+  }
+
+  template<typename T>
+  void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
+  {
+    pcl::PCLPointCloud2 pcl_pc2;
+    pcl_conversions::toPCL(cloud, pcl_pc2);
+    pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
+  }
+
+  template<typename T>
+  void moveFromROSMsg(sensor_msgs::PointCloud2 &cloud, pcl::PointCloud<T> &pcl_cloud)
+  {
+    pcl::PCLPointCloud2 pcl_pc2;
+    pcl_conversions::moveToPCL(cloud, pcl_pc2);
+    pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
+  }
+
+  /** Overload pcl::createMapping **/
+
+  template<typename PointT>
+  void createMapping(const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
+  {
+    std::vector<pcl::PCLPointField> pcl_msg_fields;
+    pcl_conversions::toPCL(msg_fields, pcl_msg_fields);
+    return createMapping<PointT>(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<sensor_msgs::PointField> fields2;
+      std::vector<int> 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<char*> (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]),
+                    reinterpret_cast<const char*> (&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<pcl::PCLPointCloud2>
+  {
+    boost::shared_ptr<pcl::PCLPointCloud2> operator() ()
+    {
+      boost::shared_ptr<pcl::PCLPointCloud2> msg(new pcl::PCLPointCloud2());
+      return msg;
+    }
+  };
+
+  namespace message_traits
+  {
+    template<>
+    struct MD5Sum<pcl::PCLPointCloud2>
+    {
+      static const char* value() { return MD5Sum<sensor_msgs::PointCloud2>::value(); }
+      static const char* value(const pcl::PCLPointCloud2&) { return value(); }
+
+      static const uint64_t static_value1 = MD5Sum<sensor_msgs::PointCloud2>::static_value1;
+      static const uint64_t static_value2 = MD5Sum<sensor_msgs::PointCloud2>::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<pcl::PCLPointCloud2>
+    {
+      static const char* value() { return DataType<sensor_msgs::PointCloud2>::value(); }
+      static const char* value(const pcl::PCLPointCloud2&) { return value(); }
+    };
+
+    template<>
+    struct Definition<pcl::PCLPointCloud2>
+    {
+      static const char* value() { return Definition<sensor_msgs::PointCloud2>::value(); }
+      static const char* value(const pcl::PCLPointCloud2&) { return value(); }
+    };
+
+    template<> struct HasHeader<pcl::PCLPointCloud2> : TrueType {};
+  } // namespace ros::message_traits
+
+  namespace serialization
+  {
+    /*
+     * Provide a custom serialization for pcl::PCLPointCloud2
+     */
+    template<>
+    struct Serializer<pcl::PCLPointCloud2>
+    {
+      template<typename Stream>
+      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<sensor_msgs::PointField> 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<typename Stream>
+      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<sensor_msgs::PointField> 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<sensor_msgs::PointField> 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<pcl::PCLPointField>
+    {
+      template<typename Stream>
+      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<typename Stream>
+      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<pcl::PCLHeader>
+    {
+      template<typename Stream>
+      inline static void write(Stream& stream, const pcl::PCLHeader& m)
+      {
+        std_msgs::Header header;
+        pcl_conversions::fromPCL(m, header);
+        stream.next(header);
+      }
+
+      template<typename Stream>
+      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__ */
diff --git a/package.xml b/package.xml
new file mode 100644
index 0000000..9ba4f0e
--- /dev/null
+++ b/package.xml
@@ -0,0 +1,33 @@
+<?xml version="1.0"?>
+<package>
+  <name>pcl_conversions</name>
+  <version>0.2.1</version>
+  <description>Provides conversions from PCL data types and ROS message types</description>
+
+  <author email="william at osrfoundation.org">William Woodall</author>
+  <maintainer email="paul at bovbel.com">Paul Bovbel</maintainer>
+  <maintainer email="bill at neautomation.com">Bill Morris</maintainer>
+
+  <license>BSD</license>
+
+  <url>http://wiki.ros.org/pcl_conversions</url>
+  <url type="repository">https://github.com/ros-perception/pcl_conversions</url>
+  <url type="bugtracker">https://github.com/ros-perception/pcl_conversions/issues</url>
+
+  <buildtool_depend>catkin</buildtool_depend>
+
+  <build_depend>cmake_modules</build_depend>
+  <build_depend>libpcl-all-dev</build_depend>
+  <build_depend>pcl_msgs</build_depend>
+  <build_depend>roscpp</build_depend>
+  <build_depend>sensor_msgs</build_depend>
+  <build_depend>std_msgs</build_depend>
+
+  <run_depend>libpcl-all</run_depend>
+  <run_depend>libpcl-all-dev</run_depend>
+  <run_depend>pcl_msgs</run_depend>
+  <run_depend>roscpp</run_depend>
+  <run_depend>sensor_msgs</run_depend>
+  <run_depend>std_msgs</run_depend>
+
+</package>
diff --git a/test/test_pcl_conversions.cpp b/test/test_pcl_conversions.cpp
new file mode 100644
index 0000000..c07720a
--- /dev/null
+++ b/test/test_pcl_conversions.cpp
@@ -0,0 +1,154 @@
+#include <string>
+
+#include "gtest/gtest.h"
+
+#include "pcl_conversions/pcl_conversions.h"
+
+namespace {
+
+class PCLConversionTests : public ::testing::Test {
+protected:
+  virtual void SetUp() {
+    pcl_image.header.frame_id = "pcl";
+    pcl_image.height = 1;
+    pcl_image.width = 2;
+    pcl_image.step = 1;
+    pcl_image.is_bigendian = true;
+    pcl_image.encoding = "bgr8";
+    pcl_image.data.resize(2);
+    pcl_image.data[0] = 0x42;
+    pcl_image.data[1] = 0x43;
+
+    pcl_pc2.header.frame_id = "pcl";
+    pcl_pc2.height = 1;
+    pcl_pc2.width = 2;
+    pcl_pc2.point_step = 1;
+    pcl_pc2.row_step = 1;
+    pcl_pc2.is_bigendian = true;
+    pcl_pc2.is_dense = true;
+    pcl_pc2.fields.resize(2);
+    pcl_pc2.fields[0].name = "XYZ";
+    pcl_pc2.fields[0].datatype = pcl::PCLPointField::INT8;
+    pcl_pc2.fields[0].count = 3;
+    pcl_pc2.fields[0].offset = 0;
+    pcl_pc2.fields[1].name = "RGB";
+    pcl_pc2.fields[1].datatype = pcl::PCLPointField::INT8;
+    pcl_pc2.fields[1].count = 3;
+    pcl_pc2.fields[1].offset = 8 * 3;
+    pcl_pc2.data.resize(2);
+    pcl_pc2.data[0] = 0x42;
+    pcl_pc2.data[1] = 0x43;
+  }
+
+  pcl::PCLImage pcl_image;
+  sensor_msgs::Image image;
+
+  pcl::PCLPointCloud2 pcl_pc2;
+  sensor_msgs::PointCloud2 pc2;
+};
+
+template<class T>
+void test_image(T &image) {
+  EXPECT_EQ(std::string("pcl"), image.header.frame_id);
+  EXPECT_EQ(1, image.height);
+  EXPECT_EQ(2, image.width);
+  EXPECT_EQ(1, image.step);
+  EXPECT_TRUE(image.is_bigendian);
+  EXPECT_EQ(std::string("bgr8"), image.encoding);
+  EXPECT_EQ(2, image.data.size());
+  EXPECT_EQ(0x42, image.data[0]);
+  EXPECT_EQ(0x43, image.data[1]);
+}
+
+TEST_F(PCLConversionTests, imageConversion) {
+  pcl_conversions::fromPCL(pcl_image, image);
+  test_image(image);
+  pcl::PCLImage pcl_image2;
+  pcl_conversions::toPCL(image, pcl_image2);
+  test_image(pcl_image2);
+}
+
+template<class T>
+void test_pc(T &pc) {
+  EXPECT_EQ(std::string("pcl"), pc.header.frame_id);
+  EXPECT_EQ(1, pc.height);
+  EXPECT_EQ(2, pc.width);
+  EXPECT_EQ(1, pc.point_step);
+  EXPECT_EQ(1, pc.row_step);
+  EXPECT_TRUE(pc.is_bigendian);
+  EXPECT_TRUE(pc.is_dense);
+  EXPECT_EQ("XYZ", pc.fields[0].name);
+  EXPECT_EQ(pcl::PCLPointField::INT8, pc.fields[0].datatype);
+  EXPECT_EQ(3, pc.fields[0].count);
+  EXPECT_EQ(0, pc.fields[0].offset);
+  EXPECT_EQ("RGB", pc.fields[1].name);
+  EXPECT_EQ(pcl::PCLPointField::INT8, pc.fields[1].datatype);
+  EXPECT_EQ(3, pc.fields[1].count);
+  EXPECT_EQ(8 * 3, pc.fields[1].offset);
+  EXPECT_EQ(2, pc.data.size());
+  EXPECT_EQ(0x42, pc.data[0]);
+  EXPECT_EQ(0x43, pc.data[1]);
+}
+
+TEST_F(PCLConversionTests, pointcloud2Conversion) {
+  pcl_conversions::fromPCL(pcl_pc2, pc2);
+  test_pc(pc2);
+  pcl::PCLPointCloud2 pcl_pc2_2;
+  pcl_conversions::toPCL(pc2, pcl_pc2_2);
+  test_pc(pcl_pc2_2);
+}
+
+} // namespace
+
+
+struct StampTestData
+{
+  const ros::Time stamp_;
+  ros::Time stamp2_;
+
+  explicit StampTestData(const ros::Time &stamp)
+    : stamp_(stamp)
+  {
+    pcl::uint64_t pcl_stamp;
+    pcl_conversions::toPCL(stamp_, pcl_stamp);
+    pcl_conversions::fromPCL(pcl_stamp, stamp2_);
+  }
+};
+
+TEST(PCLConversionStamp, Stamps)
+{
+  {
+    const StampTestData d(ros::Time(1.000001));
+    EXPECT_TRUE(d.stamp_==d.stamp2_);
+  }
+
+  {
+    const StampTestData d(ros::Time(1.999999));
+    EXPECT_TRUE(d.stamp_==d.stamp2_);
+  }
+
+  {
+    const StampTestData d(ros::Time(1.999));
+    EXPECT_TRUE(d.stamp_==d.stamp2_);
+  }
+
+  {
+    const StampTestData d(ros::Time(1423680574, 746000000));
+    EXPECT_TRUE(d.stamp_==d.stamp2_);
+  }
+
+  {
+    const StampTestData d(ros::Time(1423680629, 901000000));
+    EXPECT_TRUE(d.stamp_==d.stamp2_);
+  }
+}
+
+int main(int argc, char **argv) {
+  try {
+    ::testing::InitGoogleTest(&argc, argv);
+    return RUN_ALL_TESTS();
+  } catch (std::exception &e) {
+    std::cerr << "Unhandled Exception: " << e.what() << std::endl;
+  }
+  return 1;
+}

-- 
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/ros/pcl-conversions.git



More information about the debian-science-commits mailing list