Point Cloud Library (PCL)  1.14.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 #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 #include <numeric> // for accumulate
57 
58 namespace pcl
59 {
60  namespace detail
61  {
62  // For converting template point cloud to message.
63  template<typename PointT>
64  struct FieldAdder
65  {
66  FieldAdder (std::vector<pcl::PCLPointField>& fields) : fields_ (fields) {};
67 
68  template<typename U> void operator() ()
69  {
71  f.name = pcl::traits::name<PointT, U>::value;
72  f.offset = pcl::traits::offset<PointT, U>::value;
73  f.datatype = pcl::traits::datatype<PointT, U>::value;
74  f.count = pcl::traits::datatype<PointT, U>::size;
75  fields_.push_back (f);
76  }
77 
78  std::vector<pcl::PCLPointField>& fields_;
79  };
80 
81  // For converting message to template point cloud.
82  template<typename PointT>
83  struct FieldMapper
84  {
85  FieldMapper (const std::vector<pcl::PCLPointField>& fields,
86  std::vector<FieldMapping>& map)
87  : fields_ (fields), map_ (map)
88  {
89  }
90 
91  template<typename Tag> void
93  {
94  for (const auto& field : fields_)
95  {
96  if (FieldMatches<PointT, Tag>()(field))
97  {
98  FieldMapping mapping;
99  mapping.serialized_offset = field.offset;
100  mapping.struct_offset = pcl::traits::offset<PointT, Tag>::value;
101  mapping.size = sizeof (typename pcl::traits::datatype<PointT, Tag>::type);
102  map_.push_back (mapping);
103  return;
104  }
105  }
106  // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595
107  PCL_WARN ("Failed to find exact match for field '%s'.\n", pcl::traits::name<PointT, Tag>::value);
108  //throw pcl::InvalidConversionException (ss.str ());
109  }
110 
111  const std::vector<pcl::PCLPointField>& fields_;
112  std::vector<FieldMapping>& map_;
113  };
114 
115  inline bool
117  {
118  return (a.serialized_offset < b.serialized_offset);
119  }
120 
121  // Helps converting PCLPointCloud2 to templated point cloud. Casts fields if datatype is different.
122  template<typename PointT>
123  struct FieldCaster
124  {
125  FieldCaster (const std::vector<pcl::PCLPointField>& fields, const pcl::PCLPointCloud2& msg, const std::uint8_t* msg_data, std::uint8_t* cloud_data)
126  : fields_ (fields), msg_(msg), msg_data_(msg_data), cloud_data_(cloud_data)
127  {}
128 
129  template<typename Tag> void
131  {
132  // first check whether any field matches exactly. Then there is nothing to do because the contents are memcpy-ed elsewhere
133  for (const auto& field : fields_) {
134  if (FieldMatches<PointT, Tag>()(field)) {
135  return;
136  }
137  }
138  for (const auto& field : fields_)
139  {
140  // The following check is similar to FieldMatches, but it tests for different datatypes
141  if ((field.name == pcl::traits::name<PointT, Tag>::value) &&
142  (field.datatype != pcl::traits::datatype<PointT, Tag>::value) &&
143  ((field.count == pcl::traits::datatype<PointT, Tag>::size) ||
144  (field.count == 0 && pcl::traits::datatype<PointT, Tag>::size == 1))) {
145 #define PCL_CAST_POINT_FIELD(TYPE) case ::pcl::traits::asEnum_v<TYPE>: \
146  PCL_WARN("Will try to cast field '%s' (original type is " #TYPE "). You may loose precision during casting. Make sure that this is acceptable or choose a different point type.\n", pcl::traits::name<PointT, Tag>::value); \
147  for (std::size_t row = 0; row < msg_.height; ++row) { \
148  const std::uint8_t* row_data = msg_data_ + row * msg_.row_step; \
149  for (std::size_t col = 0; col < msg_.width; ++col) { \
150  const std::uint8_t* msg_data = row_data + col * msg_.point_step; \
151  for(std::uint32_t i=0; i<pcl::traits::datatype<PointT, Tag>::size; ++i) { \
152  *(reinterpret_cast<typename pcl::traits::datatype<PointT, Tag>::decomposed::type*>(cloud_data + pcl::traits::offset<PointT, Tag>::value) + i) = *(reinterpret_cast<const TYPE*>(msg_data + field.offset) + i); \
153  } \
154  cloud_data += sizeof (PointT); \
155  } \
156  } \
157  break;
158  // end of PCL_CAST_POINT_FIELD definition
159 
160  std::uint8_t* cloud_data = cloud_data_;
161  switch(field.datatype) {
162  PCL_CAST_POINT_FIELD(bool)
163  PCL_CAST_POINT_FIELD(std::int8_t)
164  PCL_CAST_POINT_FIELD(std::uint8_t)
165  PCL_CAST_POINT_FIELD(std::int16_t)
166  PCL_CAST_POINT_FIELD(std::uint16_t)
167  PCL_CAST_POINT_FIELD(std::int32_t)
168  PCL_CAST_POINT_FIELD(std::uint32_t)
169  PCL_CAST_POINT_FIELD(std::int64_t)
170  PCL_CAST_POINT_FIELD(std::uint64_t)
171  PCL_CAST_POINT_FIELD(float)
172  PCL_CAST_POINT_FIELD(double)
173  default: std::cout << "Unknown datatype: " << field.datatype << std::endl;
174  }
175  return;
176  }
177 #undef PCL_CAST_POINT_FIELD
178  }
179  }
180 
181  const std::vector<pcl::PCLPointField>& fields_;
183  const std::uint8_t* msg_data_;
184  std::uint8_t* cloud_data_;
185  };
186  } //namespace detail
187 
188  template<typename PointT> void
189  createMapping (const std::vector<pcl::PCLPointField>& msg_fields, MsgFieldMap& field_map)
190  {
191  // Create initial 1-1 mapping between serialized data segments and struct fields
192  detail::FieldMapper<PointT> mapper (msg_fields, field_map);
193  for_each_type< typename traits::fieldList<PointT>::type > (mapper);
194 
195  // Coalesce adjacent fields into single memcpy's where possible
196  if (field_map.size() > 1)
197  {
198  std::sort(field_map.begin(), field_map.end(), detail::fieldOrdering);
199  MsgFieldMap::iterator i = field_map.begin(), j = i + 1;
200  while (j != field_map.end())
201  {
202  // This check is designed to permit padding between adjacent fields.
203  /// @todo One could construct a pathological case where the struct has a
204  /// field where the serialized data has padding
205  if (j->serialized_offset - i->serialized_offset == j->struct_offset - i->struct_offset)
206  {
207  i->size += (j->struct_offset + j->size) - (i->struct_offset + i->size);
208  j = field_map.erase(j);
209  }
210  else
211  {
212  ++i;
213  ++j;
214  }
215  }
216  }
217  }
218 
219  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
220  * \param[in] msg the PCLPointCloud2 binary blob (note that the binary point data in msg.data will not be used!)
221  * \param[out] cloud the resultant pcl::PointCloud<T>
222  * \param[in] field_map a MsgFieldMap object
223  * \param[in] msg_data pointer to binary blob data, used instead of msg.data
224  *
225  * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) instead, except if you have a binary blob of
226  * point data that you do not want to copy into a pcl::PCLPointCloud2 in order to use fromPCLPointCloud2.
227  */
228  template <typename PointT> void
230  const MsgFieldMap& field_map, const std::uint8_t* msg_data)
231  {
232  // Copy info fields
233  cloud.header = msg.header;
234  cloud.width = msg.width;
235  cloud.height = msg.height;
236  cloud.is_dense = msg.is_dense == 1;
237 
238  // Resize cloud
239  cloud.resize (msg.width * msg.height);
240 
241  // check if there is data to copy
242  if (msg.width * msg.height == 0)
243  {
244  return;
245  }
246 
247  // Copy point data
248  std::uint8_t* cloud_data = reinterpret_cast<std::uint8_t*>(cloud.data());
249 
250  // Check if we can copy adjacent points in a single memcpy. We can do so if there
251  // is exactly one field to copy and it is the same size as the source and destination
252  // point types.
253  if (field_map.size() == 1 &&
254  field_map[0].serialized_offset == 0 &&
255  field_map[0].struct_offset == 0 &&
256  field_map[0].size == msg.point_step &&
257  field_map[0].size == sizeof(PointT))
258  {
259  const auto cloud_row_step = (sizeof (PointT) * cloud.width);
260  // Should usually be able to copy all rows at once
261  if (msg.row_step == cloud_row_step)
262  {
263  memcpy (cloud_data, msg_data, msg.width * msg.height * sizeof(PointT));
264  }
265  else
266  {
267  for (uindex_t i = 0; i < msg.height; ++i, cloud_data += cloud_row_step, msg_data += msg.row_step)
268  memcpy (cloud_data, msg_data, cloud_row_step);
269  }
270 
271  }
272  else
273  {
274  // If not, memcpy each group of contiguous fields separately
275  for (std::size_t row = 0; row < msg.height; ++row)
276  {
277  const std::uint8_t* row_data = msg_data + row * msg.row_step;
278  for (std::size_t col = 0; col < msg.width; ++col)
279  {
280  const std::uint8_t* msg_data = row_data + col * msg.point_step;
281  for (const detail::FieldMapping& mapping : field_map)
282  {
283  std::copy(msg_data + mapping.serialized_offset, msg_data + mapping.serialized_offset + mapping.size,
284  cloud_data + mapping.struct_offset);
285  }
286  cloud_data += sizeof (PointT);
287  }
288  }
289  }
290  // if any fields in msg and cloud have different datatypes but the same name, we cast them:
291  detail::FieldCaster<PointT> caster (msg.fields, msg, msg_data, reinterpret_cast<std::uint8_t*>(cloud.data()));
292  for_each_type< typename traits::fieldList<PointT>::type > (caster);
293  }
294 
295  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
296  * \param[in] msg the PCLPointCloud2 binary blob
297  * \param[out] cloud the resultant pcl::PointCloud<T>
298  * \param[in] field_map a MsgFieldMap object
299  *
300  * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) directly or create you
301  * own MsgFieldMap using:
302  *
303  * \code
304  * MsgFieldMap field_map;
305  * createMapping<PointT> (msg.fields, field_map);
306  * \endcode
307  */
308  template <typename PointT> void
310  const MsgFieldMap& field_map)
311  {
312  fromPCLPointCloud2 (msg, cloud, field_map, msg.data.data());
313  }
314 
315  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
316  * \param[in] msg the PCLPointCloud2 binary blob
317  * \param[out] cloud the resultant pcl::PointCloud<T>
318  */
319  template<typename PointT> void
321  {
322  MsgFieldMap field_map;
323  createMapping<PointT> (msg.fields, field_map);
324  fromPCLPointCloud2 (msg, cloud, field_map);
325  }
326 
327  namespace detail {
328  /** \brief Used together with `pcl::for_each_type`, copies all point fields from `cloud_data` (respecting each field offset) to `msg_data` (tightly packed).
329  */
330  template<typename PointT>
331  struct FieldCopier {
332  FieldCopier(std::uint8_t*& msg_data, const std::uint8_t*& cloud_data) : msg_data_ (msg_data), cloud_data_ (cloud_data) {};
333 
334  template<typename U> void operator() () {
335  memcpy(msg_data_, cloud_data_ + pcl::traits::offset<PointT, U>::value, sizeof(typename pcl::traits::datatype<PointT, U>::type));
336  msg_data_ += sizeof(typename pcl::traits::datatype<PointT, U>::type);
337  }
338 
339  std::uint8_t*& msg_data_;
340  const std::uint8_t*& cloud_data_;
341  };
342 
343  /** \brief Used together with `pcl::for_each_type`, creates list of all fields, and list of size of each field.
344  */
345  template<typename PointT>
347  {
348  FieldAdderAdvanced (std::vector<pcl::PCLPointField>& fields, std::vector<std::size_t>& field_sizes) : fields_ (fields), field_sizes_ (field_sizes) {};
349 
350  template<typename U> void operator() ()
351  {
353  f.name = pcl::traits::name<PointT, U>::value;
354  f.offset = pcl::traits::offset<PointT, U>::value;
355  f.datatype = pcl::traits::datatype<PointT, U>::value;
356  f.count = pcl::traits::datatype<PointT, U>::size;
357  fields_.push_back (f);
358  field_sizes_.push_back (sizeof(typename pcl::traits::datatype<PointT, U>::type)); // If field is an array, then this is the size of all array elements
359  }
360 
361  std::vector<pcl::PCLPointField>& fields_;
362  std::vector<std::size_t>& field_sizes_;
363  };
364  } // namespace detail
365 
366  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
367  * \param[in] cloud the input pcl::PointCloud<T>
368  * \param[out] msg the resultant PCLPointCloud2 binary blob
369  * \param[in] padding Many point types have padding to ensure alignment and SIMD compatibility. Setting this to true will copy the padding to the `PCLPointCloud2` (the default in older PCL versions). Setting this to false will make the data blob in `PCLPointCloud2` smaller, while still keeping all information (useful e.g. when sending msg over network or storing it). The amount of padding depends on the point type, and can in some cases be up to 50 percent.
370  */
371  template<typename PointT> void
373  {
374  // Ease the user's burden on specifying width/height for unorganized datasets
375  if (cloud.width == 0 && cloud.height == 0)
376  {
377  msg.width = cloud.size ();
378  msg.height = 1;
379  }
380  else
381  {
382  assert (cloud.size () == cloud.width * cloud.height);
383  msg.height = cloud.height;
384  msg.width = cloud.width;
385  }
386  // Fill fields metadata
387  msg.fields.clear ();
388  std::vector<std::size_t> field_sizes;
389  for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdderAdvanced<PointT>(msg.fields, field_sizes));
390  // Check if padding should be kept, or if the point type does not contain padding (then the single memcpy is faster)
391  if (padding || std::accumulate(field_sizes.begin(), field_sizes.end(), static_cast<std::size_t>(0)) == sizeof (PointT)) {
392  // Fill point cloud binary data (padding and all)
393  std::size_t data_size = sizeof (PointT) * cloud.size ();
394  msg.data.resize (data_size);
395  if (data_size)
396  {
397  memcpy(msg.data.data(), cloud.data(), data_size);
398  }
399 
400  msg.point_step = sizeof (PointT);
401  msg.row_step = (sizeof (PointT) * msg.width);
402  } else {
403  std::size_t point_size = 0;
404  for(std::size_t i=0; i<msg.fields.size(); ++i) {
405  msg.fields[i].offset = point_size; // Adjust offset when padding is removed
406  point_size += field_sizes[i];
407  }
408  msg.data.resize (point_size * cloud.size());
409  std::uint8_t* msg_data = &msg.data[0];
410  const std::uint8_t* cloud_data=reinterpret_cast<const std::uint8_t*>(&cloud[0]);
411  const std::uint8_t* end = cloud_data + sizeof (PointT) * cloud.size ();
412  pcl::detail::FieldCopier<PointT> copier(msg_data, cloud_data); // copier takes msg_data and cloud_data as references, so the two are shared
413  for (; cloud_data<end; cloud_data+=sizeof(PointT)) {
414  for_each_type< typename traits::fieldList<PointT>::type > (copier);
415  }
416 
417  msg.point_step = point_size;
418  msg.row_step = point_size * msg.width;
419  }
420  msg.header = cloud.header;
421  msg.is_dense = cloud.is_dense;
422  /// @todo msg.is_bigendian = ?;
423  }
424 
425  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
426  * \param[in] cloud the input pcl::PointCloud<T>
427  * \param[out] msg the resultant PCLPointCloud2 binary blob
428  */
429  template<typename PointT> void
431  {
432  toPCLPointCloud2 (cloud, msg, true); // true is the default in older PCL version
433  }
434 
435  /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format
436  * \param[in] cloud the point cloud message
437  * \param[out] msg the resultant pcl::PCLImage
438  * CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA>
439  * \note will throw std::runtime_error if there is a problem
440  */
441  template<typename CloudT> void
442  toPCLPointCloud2 (const CloudT& cloud, pcl::PCLImage& msg)
443  {
444  // Ease the user's burden on specifying width/height for unorganized datasets
445  if (cloud.width == 0 && cloud.height == 0)
446  throw std::runtime_error("Needs to be a dense like cloud!!");
447  else
448  {
449  if (cloud.size () != cloud.width * cloud.height)
450  throw std::runtime_error("The width and height do not match the cloud size!");
451  msg.height = cloud.height;
452  msg.width = cloud.width;
453  }
454 
455  // ensor_msgs::image_encodings::BGR8;
456  msg.header = cloud.header;
457  msg.encoding = "bgr8";
458  msg.step = msg.width * sizeof (std::uint8_t) * 3;
459  msg.data.resize (msg.step * msg.height);
460  for (std::size_t y = 0; y < cloud.height; y++)
461  {
462  for (std::size_t x = 0; x < cloud.width; x++)
463  {
464  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
465  memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(std::uint8_t));
466  }
467  }
468  }
469 
470  /** \brief Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format
471  * \param cloud the point cloud message
472  * \param msg the resultant pcl::PCLImage
473  * will throw std::runtime_error if there is a problem
474  */
475  inline void
477  {
478  const auto predicate = [](const auto& field) { return field.name == "rgb"; };
479  const auto result = std::find_if(cloud.fields.cbegin (), cloud.fields.cend (), predicate);
480  if (result == cloud.fields.end ())
481  throw std::runtime_error ("No rgb field!!");
482 
483  const auto rgb_index = std::distance(cloud.fields.begin (), result);
484  if (cloud.width == 0 && cloud.height == 0)
485  throw std::runtime_error ("Needs to be a dense like cloud!!");
486  else
487  {
488  msg.height = cloud.height;
489  msg.width = cloud.width;
490  }
491  auto rgb_offset = cloud.fields[rgb_index].offset;
492  const auto point_step = cloud.point_step;
493 
494  // pcl::image_encodings::BGR8;
495  msg.header = cloud.header;
496  msg.encoding = "bgr8";
497  msg.step = (msg.width * sizeof (std::uint8_t) * 3);
498  msg.data.resize (msg.step * msg.height);
499 
500  for (std::size_t y = 0; y < cloud.height; y++)
501  {
502  for (std::size_t x = 0; x < cloud.width; x++, rgb_offset += point_step)
503  {
504  std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
505  std::copy(&cloud.data[rgb_offset], &cloud.data[rgb_offset] + 3, pixel);
506  }
507  }
508  }
509 }
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
PointT * data() noexcept
Definition: point_cloud.h:447
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:116
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:229
void toPCLPointCloud2(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg, bool padding)
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
Definition: conversions.h:372
void createMapping(const std::vector< pcl::PCLPointField > &msg_fields, MsgFieldMap &field_map)
Definition: conversions.h:189
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.
Used together with pcl::for_each_type, creates list of all fields, and list of size of each field.
Definition: conversions.h:347
FieldAdderAdvanced(std::vector< pcl::PCLPointField > &fields, std::vector< std::size_t > &field_sizes)
Definition: conversions.h:348
std::vector< std::size_t > & field_sizes_
Definition: conversions.h:362
std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:361
FieldAdder(std::vector< pcl::PCLPointField > &fields)
Definition: conversions.h:66
std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:78
std::uint8_t * cloud_data_
Definition: conversions.h:184
const pcl::PCLPointCloud2 & msg_
Definition: conversions.h:182
const std::uint8_t * msg_data_
Definition: conversions.h:183
FieldCaster(const std::vector< pcl::PCLPointField > &fields, const pcl::PCLPointCloud2 &msg, const std::uint8_t *msg_data, std::uint8_t *cloud_data)
Definition: conversions.h:125
const std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:181
Used together with pcl::for_each_type, copies all point fields from cloud_data (respecting each field...
Definition: conversions.h:331
FieldCopier(std::uint8_t *&msg_data, const std::uint8_t *&cloud_data)
Definition: conversions.h:332
const std::uint8_t *& cloud_data_
Definition: conversions.h:340
std::uint8_t *& msg_data_
Definition: conversions.h:339
FieldMapper(const std::vector< pcl::PCLPointField > &fields, std::vector< FieldMapping > &map)
Definition: conversions.h:85
const std::vector< pcl::PCLPointField > & fields_
Definition: conversions.h:111
std::vector< FieldMapping > & map_
Definition: conversions.h:112
std::size_t serialized_offset
Definition: point_cloud.h:64