Point Cloud Library (PCL)  1.7.0
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_CONVERSIONS_H_
41 #define PCL_CONVERSIONS_H_
42 
43 #ifdef __GNUC__
44 #pragma GCC system_header
45 #endif
46 
47 #include <pcl/PCLPointField.h>
48 #include <pcl/PCLPointCloud2.h>
49 #include <pcl/PCLImage.h>
50 #include <pcl/point_cloud.h>
51 #include <pcl/point_traits.h>
52 #include <pcl/for_each_type.h>
53 #include <pcl/exceptions.h>
54 #include <pcl/console/print.h>
55 #include <boost/foreach.hpp>
56 
57 namespace pcl
58 {
59  namespace detail
60  {
61  // For converting template point cloud to message.
62  template<typename PointT>
63  struct FieldAdder
64  {
65  FieldAdder (std::vector<pcl::PCLPointField>& fields) : fields_ (fields) {};
66 
67  template<typename U> void operator() ()
68  {
74  fields_.push_back (f);
75  }
76 
77  std::vector<pcl::PCLPointField>& fields_;
78  };
79 
80  // For converting message to template point cloud.
81  template<typename PointT>
82  struct FieldMapper
83  {
84  FieldMapper (const std::vector<pcl::PCLPointField>& fields,
85  std::vector<FieldMapping>& map)
86  : fields_ (fields), map_ (map)
87  {
88  }
89 
90  template<typename Tag> void
92  {
93  BOOST_FOREACH (const pcl::PCLPointField& field, fields_)
94  {
95  if (FieldMatches<PointT, Tag>()(field))
96  {
97  FieldMapping mapping;
98  mapping.serialized_offset = field.offset;
100  mapping.size = sizeof (typename traits::datatype<PointT, Tag>::type);
101  map_.push_back (mapping);
102  return;
103  }
104  }
105  // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595
106  PCL_WARN ("Failed to find match for field '%s'.\n", traits::name<PointT, Tag>::value);
107  //throw pcl::InvalidConversionException (ss.str ());
108  }
109 
110  const std::vector<pcl::PCLPointField>& fields_;
111  std::vector<FieldMapping>& map_;
112  };
113 
114  inline bool
116  {
117  return (a.serialized_offset < b.serialized_offset);
118  }
119 
120  } //namespace detail
121 
122  template<typename PointT> void
123  createMapping (const std::vector<pcl::PCLPointField>& msg_fields, MsgFieldMap& field_map)
124  {
125  // Create initial 1-1 mapping between serialized data segments and struct fields
126  detail::FieldMapper<PointT> mapper (msg_fields, field_map);
127  for_each_type< typename traits::fieldList<PointT>::type > (mapper);
128 
129  // Coalesce adjacent fields into single memcpy's where possible
130  if (field_map.size() > 1)
131  {
132  std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering);
133  MsgFieldMap::iterator i = field_map.begin(), j = i + 1;
134  while (j != field_map.end())
135  {
136  // This check is designed to permit padding between adjacent fields.
137  /// @todo One could construct a pathological case where the struct has a
138  /// field where the serialized data has padding
139  if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset)
140  {
141  i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size);
142  j = field_map.erase(j);
143  }
144  else
145  {
146  ++i;
147  ++j;
148  }
149  }
150  }
151  }
152 
153  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
154  * \param[in] msg the PCLPointCloud2 binary blob
155  * \param[out] cloud the resultant pcl::PointCloud<T>
156  * \param[in] field_map a MsgFieldMap object
157  *
158  * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) directly or create you
159  * own MsgFieldMap using:
160  *
161  * \code
162  * MsgFieldMap field_map;
163  * createMapping<PointT> (msg.fields, field_map);
164  * \endcode
165  */
166  template <typename PointT> void
168  const MsgFieldMap& field_map)
169  {
170  // Copy info fields
171  cloud.header = msg.header;
172  cloud.width = msg.width;
173  cloud.height = msg.height;
174  cloud.is_dense = msg.is_dense == 1;
175 
176  // Copy point data
177  uint32_t num_points = msg.width * msg.height;
178  cloud.points.resize (num_points);
179  uint8_t* cloud_data = reinterpret_cast<uint8_t*>(&cloud.points[0]);
180 
181  // Check if we can copy adjacent points in a single memcpy
182  if (field_map.size() == 1 &&
183  field_map[0].serialized_offset == 0 &&
184  field_map[0].struct_offset == 0 &&
185  msg.point_step == sizeof(PointT))
186  {
187  uint32_t cloud_row_step = static_cast<uint32_t> (sizeof (PointT) * cloud.width);
188  const uint8_t* msg_data = &msg.data[0];
189  // Should usually be able to copy all rows at once
190  if (msg.row_step == cloud_row_step)
191  {
192  memcpy (cloud_data, msg_data, msg.data.size ());
193  }
194  else
195  {
196  for (uint32_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
197  memcpy (cloud_data, msg_data, cloud_row_step);
198  }
199 
200  }
201  else
202  {
203  // If not, memcpy each group of contiguous fields separately
204  for (uint32_t row = 0; row < msg.height; ++row)
205  {
206  const uint8_t* row_data = &msg.data[row * msg.row_step];
207  for (uint32_t col = 0; col < msg.width; ++col)
208  {
209  const uint8_t* msg_data = row_data + col * msg.point_step;
210  BOOST_FOREACH (const detail::FieldMapping& mapping, field_map)
211  {
212  memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size);
213  }
214  cloud_data += sizeof (PointT);
215  }
216  }
217  }
218  }
219 
220  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
221  * \param[in] msg the PCLPointCloud2 binary blob
222  * \param[out] cloud the resultant pcl::PointCloud<T>
223  */
224  template<typename PointT> void
226  {
227  MsgFieldMap field_map;
228  createMapping<PointT> (msg.fields, field_map);
229  fromPCLPointCloud2 (msg, cloud, field_map);
230  }
231 
232  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
233  * \param[in] cloud the input pcl::PointCloud<T>
234  * \param[out] msg the resultant PCLPointCloud2 binary blob
235  */
236  template<typename PointT> void
238  {
239  // Ease the user's burden on specifying width/height for unorganized datasets
240  if (cloud.width == 0 && cloud.height == 0)
241  {
242  msg.width = static_cast<uint32_t>(cloud.points.size ());
243  msg.height = 1;
244  }
245  else
246  {
247  assert (cloud.points.size () == cloud.width * cloud.height);
248  msg.height = cloud.height;
249  msg.width = cloud.width;
250  }
251 
252  // Fill point cloud binary data (padding and all)
253  size_t data_size = sizeof (PointT) * cloud.points.size ();
254  msg.data.resize (data_size);
255  memcpy (&msg.data[0], &cloud.points[0], data_size);
256 
257  // Fill fields metadata
258  msg.fields.clear ();
259  for_each_type<typename traits::fieldList<PointT>::type> (detail::FieldAdder<PointT>(msg.fields));
260 
261  msg.header = cloud.header;
262  msg.point_step = sizeof (PointT);
263  msg.row_step = static_cast<uint32_t> (sizeof (PointT) * msg.width);
264  msg.is_dense = cloud.is_dense;
265  /// @todo msg.is_bigendian = ?;
266  }
267 
268  /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format
269  * \param[in] cloud the point cloud message
270  * \param[out] msg the resultant pcl::PCLImage
271  * CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA>
272  * \note will throw std::runtime_error if there is a problem
273  */
274  template<typename CloudT> void
275  toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg)
276  {
277  // Ease the user's burden on specifying width/height for unorganized datasets
278  if (cloud.width == 0 && cloud.height == 0)
279  throw std::runtime_error("Needs to be a dense like cloud!!");
280  else
281  {
282  if (cloud.points.size () != cloud.width * cloud.height)
283  throw std::runtime_error("The width and height do not match the cloud size!");
284  msg.height = cloud.height;
285  msg.width = cloud.width;
286  }
287 
288  // ensor_msgs::image_encodings::BGR8;
289  msg.encoding = "bgr8";
290  msg.step = msg.width * sizeof (uint8_t) * 3;
291  msg.data.resize (msg.step * msg.height);
292  for (size_t y = 0; y < cloud.height; y++)
293  {
294  for (size_t x = 0; x < cloud.width; x++)
295  {
296  uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
297  memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t));
298  }
299  }
300  }
301 
302  /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format
303  * \param cloud the point cloud message
304  * \param msg the resultant pcl::PCLImage
305  * will throw std::runtime_error if there is a problem
306  */
307  inline void
309  {
310  int rgb_index = -1;
311  // Get the index we need
312  for (size_t d = 0; d < cloud.fields.size (); ++d)
313  if (cloud.fields[d].name == "rgb")
314  {
315  rgb_index = static_cast<int>(d);
316  break;
317  }
318 
319  if(rgb_index == -1)
320  throw std::runtime_error ("No rgb field!!");
321  if (cloud.width == 0 && cloud.height == 0)
322  throw std::runtime_error ("Needs to be a dense like cloud!!");
323  else
324  {
325  msg.height = cloud.height;
326  msg.width = cloud.width;
327  }
328  int rgb_offset = cloud.fields[rgb_index].offset;
329  int point_step = cloud.point_step;
330 
331  // pcl::image_encodings::BGR8;
332  msg.encoding = "bgr8";
333  msg.step = static_cast<uint32_t>(msg.width * sizeof (uint8_t) * 3);
334  msg.data.resize (msg.step * msg.height);
335 
336  for (size_t y = 0; y < cloud.height; y++)
337  {
338  for (size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
339  {
340  uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
341  memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof (uint8_t));
342  }
343  }
344  }
345 }
346 
347 #endif //#ifndef PCL_CONVERSIONS_H_