Point Cloud Library (PCL)
1.7.0
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2010-2012, Willow Garage, Inc. 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of the copyright holder(s) nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior 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 * $Id$ 00037 * 00038 */ 00039 00040 #ifndef PCL_ROS_CONVERSIONS_H_ 00041 #define PCL_ROS_CONVERSIONS_H_ 00042 00043 #ifdef __DEPRECATED 00044 #warning The <pcl/ros/conversions.h> header is deprecated. please use \ 00045 <pcl/conversions.h> instead. 00046 #endif 00047 00048 #include <pcl/conversions.h> 00049 00050 namespace pcl 00051 { 00052 /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map. 00053 * \param[in] msg the PCLPointCloud2 binary blob 00054 * \param[out] cloud the resultant pcl::PointCloud<T> 00055 * \param[in] field_map a MsgFieldMap object 00056 * 00057 * \note Use fromROSMsg (PCLPointCloud2, PointCloud<T>) directly or create you 00058 * own MsgFieldMap using: 00059 * 00060 * \code 00061 * MsgFieldMap field_map; 00062 * createMapping<PointT> (msg.fields, field_map); 00063 * \endcode 00064 */ 00065 PCL_DEPRECATED (template <typename PointT> void fromROSMsg ( 00066 const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud, 00067 const MsgFieldMap& field_map), 00068 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead."); 00069 00070 template <typename PointT> void 00071 fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud, 00072 const MsgFieldMap& field_map) 00073 { 00074 fromPCLPointCloud2 (msg, cloud, field_map); 00075 } 00076 00077 /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object. 00078 * \param[in] msg the PCLPointCloud2 binary blob 00079 * \param[out] cloud the resultant pcl::PointCloud<T> 00080 */ 00081 PCL_DEPRECATED (template<typename PointT> void fromROSMsg ( 00082 const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud), 00083 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead."); 00084 template<typename PointT> void 00085 fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud) 00086 { 00087 fromPCLPointCloud2 (msg, cloud); 00088 } 00089 00090 /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob. 00091 * \param[in] cloud the input pcl::PointCloud<T> 00092 * \param[out] msg the resultant PCLPointCloud2 binary blob 00093 */ 00094 PCL_DEPRECATED (template<typename PointT> void toROSMsg ( 00095 const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg), 00096 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead."); 00097 template<typename PointT> void 00098 toROSMsg (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg) 00099 { 00100 toPCLPointCloud2 (cloud, msg); 00101 } 00102 00103 /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format 00104 * \param[in] cloud the point cloud message 00105 * \param[out] msg the resultant pcl::PCLImage 00106 * CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA> 00107 * \note will throw std::runtime_error if there is a problem 00108 */ 00109 PCL_DEPRECATED (template<typename CloudT> void toROSMsg ( 00110 const CloudT& cloud, pcl::PCLImage& msg), 00111 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead."); 00112 template<typename CloudT> void 00113 toROSMsg (const CloudT& cloud, pcl::PCLImage& msg) 00114 { 00115 toPCLPointCloud2 (cloud, msg); 00116 } 00117 00118 /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format 00119 * \param cloud the point cloud message 00120 * \param msg the resultant pcl::PCLImage 00121 * will throw std::runtime_error if there is a problem 00122 */ 00123 PCL_DEPRECATED (inline void toROSMsg ( 00124 const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg), 00125 "pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead."); 00126 inline void 00127 toROSMsg (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg) 00128 { 00129 toPCLPointCloud2 (cloud, msg); 00130 } 00131 } 00132 00133 #endif //#ifndef PCL_ROS_CONVERSIONS_H_