00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2013, Open Source Robotics Foundation, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Open Source Robotics Foundation, Inc. nor 00018 * the names of its contributors may be used to endorse or promote 00019 * products derived from this software without specific prior 00020 * written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 */ 00035 00036 #ifndef INDIGO_PCL_CONVERSIONS_H__ 00037 #define INDIGO_PCL_CONVERSIONS_H__ 00038 00039 #include <vector> 00040 00041 #include <ros/ros.h> 00042 00043 #include <pcl/conversions.h> 00044 00045 #include <pcl/PCLHeader.h> 00046 #include <std_msgs/Header.h> 00047 00048 #include <pcl/PCLImage.h> 00049 #include <sensor_msgs/Image.h> 00050 00051 #include <pcl/PCLPointField.h> 00052 #include <sensor_msgs/PointField.h> 00053 00054 #include <pcl/PCLPointCloud2.h> 00055 #include <sensor_msgs/PointCloud2.h> 00056 00057 #include <pcl/PointIndices.h> 00058 #include <pcl_msgs/PointIndices.h> 00059 00060 #include <pcl/ModelCoefficients.h> 00061 #include <pcl_msgs/ModelCoefficients.h> 00062 00063 #include <pcl/Vertices.h> 00064 #include <pcl_msgs/Vertices.h> 00065 00066 #include <pcl/PolygonMesh.h> 00067 #include <pcl_msgs/PolygonMesh.h> 00068 00069 #include <pcl/io/pcd_io.h> 00070 00071 #include <Eigen/StdVector> 00072 #include <Eigen/Geometry> 00073 00074 namespace pcl_conversions { 00075 00078 inline 00079 void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp) 00080 { 00081 stamp.fromNSec(pcl_stamp * 1e3); // Convert from us to ns 00082 } 00083 00084 inline 00085 void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp) 00086 { 00087 pcl_stamp = stamp.toNSec() / 1e3; // Convert from ns to us 00088 } 00089 00090 inline 00091 ros::Time fromPCL(const pcl::uint64_t &pcl_stamp) 00092 { 00093 ros::Time stamp; 00094 fromPCL(pcl_stamp, stamp); 00095 return stamp; 00096 } 00097 00098 inline 00099 pcl::uint64_t toPCL(const ros::Time &stamp) 00100 { 00101 pcl::uint64_t pcl_stamp; 00102 toPCL(stamp, pcl_stamp); 00103 return pcl_stamp; 00104 } 00105 00108 //inline 00109 //void fromPCL(const pcl::PCLHeader &pcl_header, std_msgs::Header &header) 00110 //{ 00111 //fromPCL(pcl_header.stamp, header.stamp); 00112 //header.seq = pcl_header.seq; 00113 //header.frame_id = pcl_header.frame_id; 00114 //} 00115 00116 //inline 00117 //void toPCL(const std_msgs::Header &header, pcl::PCLHeader &pcl_header) 00118 //{ 00119 //toPCL(header.stamp, pcl_header.stamp); 00120 //pcl_header.seq = header.seq; 00121 //pcl_header.frame_id = header.frame_id; 00122 //} 00123 00124 //inline 00125 //std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header) 00126 //{ 00127 //std_msgs::Header header; 00128 //fromPCL(pcl_header, header); 00129 //return header; 00130 //} 00131 00132 //inline 00133 //pcl::PCLHeader toPCL(const std_msgs::Header &header) 00134 //{ 00135 //pcl::PCLHeader pcl_header; 00136 //toPCL(header, pcl_header); 00137 //return pcl_header; 00138 //} 00139 00140 } 00141 00142 #endif