Point Cloud Library (PCL)  1.12.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 <boost/foreach.hpp>
55 
56 namespace pcl
57 {
58  namespace detail
59  {
60  // For converting template point cloud to message.
61  template<typename PointT>
62  struct FieldAdder
63  {
64  FieldAdder (std::vector<pcl::PCLPointField>& fields) : fields_ (fields) {};
65 
66  template<typename U> void operator() ()
67  {
69  f.name = pcl::traits::name<PointT, U>::value;
70  f.offset = pcl::traits::offset<PointT, U>::value;
71  f.datatype = pcl::traits::datatype<PointT, U>::value;
72  f.count = pcl::traits::datatype<PointT, U>::size;
73  fields_.push_back (f);
74  }
75 
76  std::vector<pcl::PCLPointField>& fields_;
77  };
78 
79  // For converting message to template point cloud.
80  template<typename PointT>
81  struct FieldMapper
82  {
83  FieldMapper (const std::vector<pcl::PCLPointField>& fields,
84  std::vector<FieldMapping>& map)
85  : fields_ (fields), map_ (map)
86  {
87  }
88 
89  template<typename Tag> void
91  {
92  for (const auto& field : fields_)
93  {
94  if (FieldMatches<PointT, Tag>()(field))
95  {
96  FieldMapping mapping;
97  mapping.serialized_offset = field.offset;
98  mapping.struct_offset = pcl::traits::offset<PointT, Tag>::value;
99  mapping.size = sizeof (typename pcl::traits::datatype<PointT, Tag>::type);
100  map_.push_back (mapping);
101  return;
102  }
103  }
104  // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595
105  PCL_WARN ("Failed to find match for field '%s'.\n", pcl::traits::name<PointT, Tag>::value);
106  //throw pcl::InvalidConversionException (ss.str ());
107  }
108 
109  const std::vector<pcl::PCLPointField>& fields_;
110  std::vector<FieldMapping>& map_;
111  };
112 
113  inline bool
115  {
116  return (a.serialized_offset < b.serialized_offset);
117  }
118 
119  } //namespace detail
120 
121  template<typename PointT> void
122  createMapping (const std::vector<pcl::PCLPointField>& msg_fields, MsgFieldMap& field_map)
123  {
124  // Create initial 1-1 mapping between serialized data segments and struct fields
125  detail::FieldMapper<PointT> mapper (msg_fields, field_map);
126  for_each_type< typename traits::fieldList<PointT>::type > (mapper);
127 
128  // Coalesce adjacent fields into single memcpy's where possible
129  if (field_map.size() > 1)
130  {
131  std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering);
132  MsgFieldMap::iterator i = field_map.begin(), j = i + 1;
133  while (j != field_map.end())
134  {
135  // This check is designed to permit padding between adjacent fields.
136  /// @todo One could construct a pathological case where the struct has a
137  /// field where the serialized data has padding
138  if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset)
139  {
140  i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size);
141  j = field_map.erase(j);
142  }
143  else
144  {
145  ++i;
146  ++j;
147  }
148  }
149  }
150  }
151 
152  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
153  * \param[in] msg the PCLPointCloud2 binary blob
154  * \param[out] cloud the resultant pcl::PointCloud<T>
155  * \param[in] field_map a MsgFieldMap object
156  *
157  * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) directly or create you
158  * own MsgFieldMap using:
159  *
160  * \code
161  * MsgFieldMap field_map;
162  * createMapping<PointT> (msg.fields, field_map);
163  * \endcode
164  */
165  template <typename PointT> void
167  const MsgFieldMap& field_map)
168  {
169  // Copy info fields
170  cloud.header = msg.header;
171  cloud.width = msg.width;
172  cloud.height = msg.height;
173  cloud.is_dense = msg.is_dense == 1;
174 
175  // Copy point data
176  cloud.resize (msg.width * msg.height);
177  std::uint8_t* cloud_data = reinterpret_cast<std::uint8_t*>(&cloud[0]);
178 
179  // Check if we can copy adjacent points in a single memcpy. We can do so if there
180  // is exactly one field to copy and it is the same size as the source and destination
181  // point types.
182  if (field_map.size() == 1 &&
183  field_map[0].serialized_offset == 0 &&
184  field_map[0].struct_offset == 0 &&
185  field_map[0].size == msg.point_step &&
186  field_map[0].size == sizeof(PointT))
187  {
188  const auto cloud_row_step = (sizeof (PointT) * cloud.width);
189  const std::uint8_t* msg_data = &msg.data[0];
190  // Should usually be able to copy all rows at once
191  if (msg.row_step == cloud_row_step)
192  {
193  memcpy (cloud_data, msg_data, msg.data.size ());
194  }
195  else
196  {
197  for (uindex_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
198  memcpy (cloud_data, msg_data, cloud_row_step);
199  }
200 
201  }
202  else
203  {
204  // If not, memcpy each group of contiguous fields separately
205  for (uindex_t row = 0; row < msg.height; ++row)
206  {
207  const std::uint8_t* row_data = &msg.data[row * msg.row_step];
208  for (uindex_t col = 0; col < msg.width; ++col)
209  {
210  const std::uint8_t* msg_data = row_data + col * msg.point_step;
211  for (const detail::FieldMapping& mapping : field_map)
212  {
213  memcpy (cloud_data + mapping.struct_offset, msg_data + mapping.serialized_offset, mapping.size);
214  }
215  cloud_data += sizeof (PointT);
216  }
217  }
218  }
219  }
220 
221  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
222  * \param[in] msg the PCLPointCloud2 binary blob
223  * \param[out] cloud the resultant pcl::PointCloud<T>
224  */
225  template<typename PointT> void
227  {
228  MsgFieldMap field_map;
229  createMapping<PointT> (msg.fields, field_map);
230  fromPCLPointCloud2 (msg, cloud, field_map);
231  }
232 
233  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
234  * \param[in] cloud the input pcl::PointCloud<T>
235  * \param[out] msg the resultant PCLPointCloud2 binary blob
236  */
237  template<typename PointT> void
239  {
240  // Ease the user's burden on specifying width/height for unorganized datasets
241  if (cloud.width == 0 && cloud.height == 0)
242  {
243  msg.width = cloud.size ();
244  msg.height = 1;
245  }
246  else
247  {
248  assert (cloud.size () == cloud.width * cloud.height);
249  msg.height = cloud.height;
250  msg.width = cloud.width;
251  }
252 
253  // Fill point cloud binary data (padding and all)
254  std::size_t data_size = sizeof (PointT) * cloud.size ();
255  msg.data.resize (data_size);
256  if (data_size)
257  {
258  memcpy(&msg.data[0], &cloud[0], data_size);
259  }
260 
261  // Fill fields metadata
262  msg.fields.clear ();
263  for_each_type<typename traits::fieldList<PointT>::type> (detail::FieldAdder<PointT>(msg.fields));
264 
265  msg.header = cloud.header;
266  msg.point_step = sizeof (PointT);
267  msg.row_step = (sizeof (PointT) * msg.width);
268  msg.is_dense = cloud.is_dense;
269  /// @todo msg.is_bigendian = ?;
270  }
271 
272  /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format
273  * \param[in] cloud the point cloud message
274  * \param[out] msg the resultant pcl::PCLImage
275  * CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA>
276  * \note will throw std::runtime_error if there is a problem
277  */
278  template<typename CloudT> void
279  toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg)
280  {
281  // Ease the user's burden on specifying width/height for unorganized datasets
282  if (cloud.width == 0 && cloud.height == 0)
283  throw std::runtime_error("Needs to be a dense like cloud!!");
284  else
285  {
286  if (cloud.size () != cloud.width * cloud.height)
287  throw std::runtime_error("The width and height do not match the cloud size!");
288  msg.height = cloud.height;
289  msg.width = cloud.width;
290  }
291 
292  // ensor_msgs::image_encodings::BGR8;
293  msg.header = cloud.header;
294  msg.encoding = "bgr8";
295  msg.step = msg.width * sizeof (std::uint8_t) * 3;
296  msg.data.resize (msg.step * msg.height);
297  for (std::size_t y = 0; y < cloud.height; y++)
298  {
299  for (std::size_t x = 0; x < cloud.width; x++)
300  {
301  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
302  memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(std::uint8_t));
303  }
304  }
305  }
306 
307  /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format
308  * \param cloud the point cloud message
309  * \param msg the resultant pcl::PCLImage
310  * will throw std::runtime_error if there is a problem
311  */
312  inline void
314  {
315  const auto predicate = [](const auto& field) { return field.name == "rgb"; };
316  const auto result = std::find_if(cloud.fields.cbegin (), cloud.fields.cend (), predicate);
317  if (result == cloud.fields.end ())
318  throw std::runtime_error ("No rgb field!!");
319 
320  const auto rgb_index = std::distance(cloud.fields.begin (), result);
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  auto rgb_offset = cloud.fields[rgb_index].offset;
329  const auto point_step = cloud.point_step;
330 
331  // pcl::image_encodings::BGR8;
332  msg.header = cloud.header;
333  msg.encoding = "bgr8";
334  msg.step = (msg.width * sizeof (std::uint8_t) * 3);
335  msg.data.resize (msg.step * msg.height);
336 
337  for (std::size_t y = 0; y < cloud.height; y++)
338  {
339  for (std::size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
340  {
341  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
342  memcpy (pixel, &(cloud.data[rgb_offset]), 3 * sizeof (std::uint8_t));
343  }
344  }
345  }
346 }
pcl::PCLImage::step
uindex_t step
Definition: PCLImage.h:21
pcl
Definition: convolution.h:46
pcl::PCLImage::data
std::vector< std::uint8_t > data
Definition: PCLImage.h:23
pcl::PCLImage::encoding
std::string encoding
Definition: PCLImage.h:18
pcl::PCLPointCloud2::point_step
uindex_t point_step
Definition: PCLPointCloud2.h:27
pcl::PointCloud::height
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:400
pcl::geometry::distance
float distance(const PointT &p1, const PointT &p2)
Definition: geometry.h:60
pcl::PCLPointCloud2::width
uindex_t width
Definition: PCLPointCloud2.h:21
pcl::PCLPointCloud2::row_step
uindex_t row_step
Definition: PCLPointCloud2.h:28
pcl::PCLPointField::count
uindex_t count
Definition: PCLPointField.h:18
pcl::detail::fieldOrdering
bool fieldOrdering(const FieldMapping &a, const FieldMapping &b)
Definition: conversions.h:114
pcl::PCLImage::width
uindex_t width
Definition: PCLImage.h:17
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
pcl::PCLPointCloud2::height
uindex_t height
Definition: PCLPointCloud2.h:20
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:674
pcl::PCLImage::header
::pcl::PCLHeader header
Definition: PCLImage.h:14
pcl::PCLPointCloud2::is_dense
std::uint8_t is_dense
Definition: PCLPointCloud2.h:32
pcl::PCLPointCloud2::header
::pcl::PCLHeader header
Definition: PCLPointCloud2.h:18
pcl::detail::FieldMapping
Definition: point_cloud.h:62
pcl::PCLPointField::offset
uindex_t offset
Definition: PCLPointField.h:16
pcl::PCLPointField::datatype
std::uint8_t datatype
Definition: PCLPointField.h:17
pcl::detail::FieldMapper
Definition: conversions.h:81
pcl::detail::FieldMapping::size
std::size_t size
Definition: point_cloud.h:66
pcl::detail::FieldMapper::FieldMapper
FieldMapper(const std::vector< pcl::PCLPointField > &fields, std::vector< FieldMapping > &map)
Definition: conversions.h:83
pcl::PointCloud::width
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:398
pcl::PCLPointCloud2::fields
std::vector<::pcl::PCLPointField > fields
Definition: PCLPointCloud2.h:23
pcl::detail::FieldMapper::operator()
void operator()()
Definition: conversions.h:90
pcl::detail::FieldAdder::fields_
std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:76
pcl::PointCloud::is_dense
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
pcl::PointCloud::resize
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:462
pcl::PointCloud::header
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:392
pcl::PCLPointCloud2::data
std::vector< std::uint8_t > data
Definition: PCLPointCloud2.h:30
pcl::PCLPointCloud2
Definition: PCLPointCloud2.h:16
pcl::PointCloud::size
std::size_t size() const
Definition: point_cloud.h:443
pcl::detail::FieldAdder::FieldAdder
FieldAdder(std::vector< pcl::PCLPointField > &fields)
Definition: conversions.h:64
pcl::detail::FieldAdder::operator()
void operator()()
Definition: conversions.h:66
pcl::PCLImage
Definition: PCLImage.h:12
pcl::PCLImage::height
uindex_t height
Definition: PCLImage.h:16
pcl::PCLPointField::name
std::string name
Definition: PCLPointField.h:14
pcl::detail::FieldMapper::fields_
const std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:109
pcl::detail::FieldMapping::serialized_offset
std::size_t serialized_offset
Definition: point_cloud.h:64
pcl::PCLPointField
Definition: PCLPointField.h:12
pcl::toPCLPointCloud2
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:238
pcl::FieldMatches
Definition: PCLPointField.h:53
pcl::MsgFieldMap
std::vector< detail::FieldMapping > MsgFieldMap
Definition: point_cloud.h:72
pcl::createMapping
void createMapping(const std::vector< pcl::PCLPointField > &msg_fields, MsgFieldMap &field_map)
Definition: conversions.h:122
pcl::uindex_t
detail::int_type_t< detail::index_type_size, false > uindex_t
Type used for an unsigned index in PCL.
Definition: types.h:120
pcl::detail::FieldAdder
Definition: conversions.h:62
pcl::detail::FieldMapping::struct_offset
std::size_t struct_offset
Definition: point_cloud.h:65
pcl::detail::FieldMapper::map_
std::vector< FieldMapping > & map_
Definition: conversions.h:110
pcl::fromPCLPointCloud2
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:166