Point Cloud Library (PCL)  1.13.0-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 #pragma once
41 
42 #ifdef __GNUC__
43 #pragma GCC system_header
44 #endif
45 
46 #include <pcl/PCLPointField.h>
47 #include <pcl/PCLPointCloud2.h>
48 #include <pcl/PCLImage.h>
49 #include <pcl/point_cloud.h>
50 #include <pcl/type_traits.h>
51 #include <pcl/for_each_type.h>
52 #include <pcl/console/print.h>
53 
54 #include <algorithm>
55 #include <iterator>
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  {
70  f.name = pcl::traits::name<PointT, U>::value;
71  f.offset = pcl::traits::offset<PointT, U>::value;
72  f.datatype = pcl::traits::datatype<PointT, U>::value;
73  f.count = pcl::traits::datatype<PointT, U>::size;
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  for (const auto& field : fields_)
94  {
95  if (FieldMatches<PointT, Tag>()(field))
96  {
97  FieldMapping mapping;
98  mapping.serialized_offset = field.offset;
99  mapping.struct_offset = pcl::traits::offset<PointT, Tag>::value;
100  mapping.size = sizeof (typename pcl::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", pcl::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 (note that the binary point data in msg.data will not be used!)
155  * \param[out] cloud the resultant pcl::PointCloud<T>
156  * \param[in] field_map a MsgFieldMap object
157  * \param[in] msg_data pointer to binary blob data, used instead of msg.data
158  *
159  * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) instead, except if you have a binary blob of
160  * point data that you do not want to copy into a pcl::PCLPointCloud2 in order to use fromPCLPointCloud2.
161  */
162  template <typename PointT> void
164  const MsgFieldMap& field_map, const std::uint8_t* msg_data)
165  {
166  // Copy info fields
167  cloud.header = msg.header;
168  cloud.width = msg.width;
169  cloud.height = msg.height;
170  cloud.is_dense = msg.is_dense == 1;
171 
172  // Copy point data
173  cloud.resize (msg.width * msg.height);
174  std::uint8_t* cloud_data = reinterpret_cast<std::uint8_t*>(&cloud[0]);
175 
176  // Check if we can copy adjacent points in a single memcpy. We can do so if there
177  // is exactly one field to copy and it is the same size as the source and destination
178  // point types.
179  if (field_map.size() == 1 &&
180  field_map[0].serialized_offset == 0 &&
181  field_map[0].struct_offset == 0 &&
182  field_map[0].size == msg.point_step &&
183  field_map[0].size == sizeof(PointT))
184  {
185  const auto cloud_row_step = (sizeof (PointT) * cloud.width);
186  // Should usually be able to copy all rows at once
187  if (msg.row_step == cloud_row_step)
188  {
189  memcpy (cloud_data, msg_data, msg.width * msg.height * sizeof(PointT));
190  }
191  else
192  {
193  for (uindex_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
194  memcpy (cloud_data, msg_data, cloud_row_step);
195  }
196 
197  }
198  else
199  {
200  // If not, memcpy each group of contiguous fields separately
201  for (std::size_t row = 0; row < msg.height; ++row)
202  {
203  const std::uint8_t* row_data = msg_data + row * msg.row_step;
204  for (std::size_t col = 0; col < msg.width; ++col)
205  {
206  const std::uint8_t* msg_data = row_data + col * msg.point_step;
207  for (const detail::FieldMapping& mapping : field_map)
208  {
209  std::copy(msg_data + mapping.serialized_offset, msg_data + mapping.serialized_offset + mapping.size,
210  cloud_data + mapping.struct_offset);
211  }
212  cloud_data += sizeof (PointT);
213  }
214  }
215  }
216  }
217 
218  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
219  * \param[in] msg the PCLPointCloud2 binary blob
220  * \param[out] cloud the resultant pcl::PointCloud<T>
221  * \param[in] field_map a MsgFieldMap object
222  *
223  * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) directly or create you
224  * own MsgFieldMap using:
225  *
226  * \code
227  * MsgFieldMap field_map;
228  * createMapping<PointT> (msg.fields, field_map);
229  * \endcode
230  */
231  template <typename PointT> void
233  const MsgFieldMap& field_map)
234  {
235  fromPCLPointCloud2 (msg, cloud, field_map, msg.data.data());
236  }
237 
238  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
239  * \param[in] msg the PCLPointCloud2 binary blob
240  * \param[out] cloud the resultant pcl::PointCloud<T>
241  */
242  template<typename PointT> void
244  {
245  MsgFieldMap field_map;
246  createMapping<PointT> (msg.fields, field_map);
247  fromPCLPointCloud2 (msg, cloud, field_map);
248  }
249 
250  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
251  * \param[in] cloud the input pcl::PointCloud<T>
252  * \param[out] msg the resultant PCLPointCloud2 binary blob
253  */
254  template<typename PointT> void
256  {
257  // Ease the user's burden on specifying width/height for unorganized datasets
258  if (cloud.width == 0 && cloud.height == 0)
259  {
260  msg.width = cloud.size ();
261  msg.height = 1;
262  }
263  else
264  {
265  assert (cloud.size () == cloud.width * cloud.height);
266  msg.height = cloud.height;
267  msg.width = cloud.width;
268  }
269 
270  // Fill point cloud binary data (padding and all)
271  std::size_t data_size = sizeof (PointT) * cloud.size ();
272  msg.data.resize (data_size);
273  if (data_size)
274  {
275  memcpy(&msg.data[0], &cloud[0], data_size);
276  }
277 
278  // Fill fields metadata
279  msg.fields.clear ();
280  for_each_type<typename traits::fieldList<PointT>::type> (detail::FieldAdder<PointT>(msg.fields));
281 
282  msg.header = cloud.header;
283  msg.point_step = sizeof (PointT);
284  msg.row_step = (sizeof (PointT) * msg.width);
285  msg.is_dense = cloud.is_dense;
286  /// @todo msg.is_bigendian = ?;
287  }
288 
289  /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format
290  * \param[in] cloud the point cloud message
291  * \param[out] msg the resultant pcl::PCLImage
292  * CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA>
293  * \note will throw std::runtime_error if there is a problem
294  */
295  template<typename CloudT> void
296  toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg)
297  {
298  // Ease the user's burden on specifying width/height for unorganized datasets
299  if (cloud.width == 0 && cloud.height == 0)
300  throw std::runtime_error("Needs to be a dense like cloud!!");
301  else
302  {
303  if (cloud.size () != cloud.width * cloud.height)
304  throw std::runtime_error("The width and height do not match the cloud size!");
305  msg.height = cloud.height;
306  msg.width = cloud.width;
307  }
308 
309  // ensor_msgs::image_encodings::BGR8;
310  msg.header = cloud.header;
311  msg.encoding = "bgr8";
312  msg.step = msg.width * sizeof (std::uint8_t) * 3;
313  msg.data.resize (msg.step * msg.height);
314  for (std::size_t y = 0; y < cloud.height; y++)
315  {
316  for (std::size_t x = 0; x < cloud.width; x++)
317  {
318  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
319  memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(std::uint8_t));
320  }
321  }
322  }
323 
324  /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format
325  * \param cloud the point cloud message
326  * \param msg the resultant pcl::PCLImage
327  * will throw std::runtime_error if there is a problem
328  */
329  inline void
331  {
332  const auto predicate = [](const auto& field) { return field.name == "rgb"; };
333  const auto result = std::find_if(cloud.fields.cbegin (), cloud.fields.cend (), predicate);
334  if (result == cloud.fields.end ())
335  throw std::runtime_error ("No rgb field!!");
336 
337  const auto rgb_index = std::distance(cloud.fields.begin (), result);
338  if (cloud.width == 0 && cloud.height == 0)
339  throw std::runtime_error ("Needs to be a dense like cloud!!");
340  else
341  {
342  msg.height = cloud.height;
343  msg.width = cloud.width;
344  }
345  auto rgb_offset = cloud.fields[rgb_index].offset;
346  const auto point_step = cloud.point_step;
347 
348  // pcl::image_encodings::BGR8;
349  msg.header = cloud.header;
350  msg.encoding = "bgr8";
351  msg.step = (msg.width * sizeof (std::uint8_t) * 3);
352  msg.data.resize (msg.step * msg.height);
353 
354  for (std::size_t y = 0; y < cloud.height; y++)
355  {
356  for (std::size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
357  {
358  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
359  std::copy(&cloud.data[rgb_offset], &cloud.data[rgb_offset] + 3, pixel);
360  }
361  }
362  }
363 }
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition: point_cloud.h:403
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:462
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:398
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:392
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:400
std::size_t size() const
Definition: point_cloud.h:443
bool fieldOrdering(const FieldMapping &a, const FieldMapping &b)
Definition: conversions.h:115
float distance(const PointT &p1, const PointT &p2)
Definition: geometry.h:60
detail::int_type_t< detail::index_type_size, false > uindex_t
Type used for an unsigned index in PCL.
Definition: types.h:120
void fromPCLPointCloud2(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map, const std::uint8_t *msg_data)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
Definition: conversions.h:163
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:255
void createMapping(const std::vector< pcl::PCLPointField > &msg_fields, MsgFieldMap &field_map)
Definition: conversions.h:123
std::vector< detail::FieldMapping > MsgFieldMap
Definition: point_cloud.h:72
uindex_t step
Definition: PCLImage.h:21
uindex_t height
Definition: PCLImage.h:16
std::string encoding
Definition: PCLImage.h:18
std::vector< std::uint8_t > data
Definition: PCLImage.h:23
uindex_t width
Definition: PCLImage.h:17
::pcl::PCLHeader header
Definition: PCLImage.h:14
std::uint8_t is_dense
std::vector<::pcl::PCLPointField > fields
::pcl::PCLHeader header
std::vector< std::uint8_t > data
std::string name
Definition: PCLPointField.h:14
std::uint8_t datatype
Definition: PCLPointField.h:17
A point structure representing Euclidean xyz coordinates, and the RGB color.
FieldAdder(std::vector< pcl::PCLPointField > &fields)
Definition: conversions.h:65
std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:77
FieldMapper(const std::vector< pcl::PCLPointField > &fields, std::vector< FieldMapping > &map)
Definition: conversions.h:84
const std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:110
std::vector< FieldMapping > & map_
Definition: conversions.h:111
std::size_t serialized_offset
Definition: point_cloud.h:64