Point Cloud Library (PCL)  1.8.1-dev
conversions.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  *
38  */
39 
40 #ifndef PCL_ROS_CONVERSIONS_H_
41 #define PCL_ROS_CONVERSIONS_H_
42 
43 #ifdef __DEPRECATED
44 #warning The <pcl/ros/conversions.h> header is deprecated. please use \
45 <pcl/conversions.h> instead.
46 #endif
47 
48 #include <pcl/conversions.h>
49 
50 namespace pcl
51 {
52  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
53  * \param[in] msg the PCLPointCloud2 binary blob
54  * \param[out] cloud the resultant pcl::PointCloud<T>
55  * \param[in] field_map a MsgFieldMap object
56  *
57  * \note Use fromROSMsg (PCLPointCloud2, PointCloud<T>) directly or create you
58  * own MsgFieldMap using:
59  *
60  * \code
61  * MsgFieldMap field_map;
62  * createMapping<PointT> (msg.fields, field_map);
63  * \endcode
64  */
65  template <typename PointT>
66  PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
67  void
68  fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud,
69  const MsgFieldMap& field_map)
70  {
71  fromPCLPointCloud2 (msg, cloud, field_map);
72  }
73 
74  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
75  * \param[in] msg the PCLPointCloud2 binary blob
76  * \param[out] cloud the resultant pcl::PointCloud<T>
77  */
78  template<typename PointT>
79  PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
80  void
81  fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud)
82  {
83  fromPCLPointCloud2 (msg, cloud);
84  }
85 
86  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
87  * \param[in] cloud the input pcl::PointCloud<T>
88  * \param[out] msg the resultant PCLPointCloud2 binary blob
89  */
90  template<typename PointT>
91  PCL_DEPRECATED ("pcl::toROSMsg is deprecated, please use toPCLPointCloud2 instead.")
92  void
93  toROSMsg (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg)
94  {
95  toPCLPointCloud2 (cloud, msg);
96  }
97 
98  /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format
99  * \param[in] cloud the point cloud message
100  * \param[out] msg the resultant pcl::PCLImage
101  * CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA>
102  * \note will throw std::runtime_error if there is a problem
103  */
104  template<typename CloudT>
105  PCL_DEPRECATED ("pcl::toROSMsg is deprecated, please use toPCLPointCloud2 instead.")
106  void
107  toROSMsg (const CloudT& cloud, pcl::PCLImage& msg)
108  {
109  toPCLPointCloud2 (cloud, msg);
110  }
111 
112  /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format
113  * \param cloud the point cloud message
114  * \param msg the resultant pcl::PCLImage
115  * will throw std::runtime_error if there is a problem
116  */
117  inline void
118  PCL_DEPRECATED ("pcl::toROSMsg is deprecated, please use toPCLPointCloud2 instead.")
119  toROSMsg (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg)
120  {
121  toPCLPointCloud2 (cloud, msg);
122  }
123 }
124 
125 #endif //#ifndef PCL_ROS_CONVERSIONS_H_
void fromROSMsg(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map...
Definition: conversions.h:68
void fromPCLPointCloud2(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map...
Definition: conversions.h:169
PointCloud represents the base class in PCL for storing collections of 3D points. ...
void toPCLPointCloud2(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg)
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
Definition: conversions.h:242
void toROSMsg(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg)
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
Definition: conversions.h:93
A point structure representing Euclidean xyz coordinates, and the RGB color.
std::vector< detail::FieldMapping > MsgFieldMap
Definition: point_cloud.h:65