Ignition Msgs

API Reference

8.4.0
PointCloudPackedUtils.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2022 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 // Inspired by
19 // https://github.com/ros/common_msgs/blob/275b09a/sensor_msgs/include/sensor_msgs/point_cloud2_iterator.h
20 
21 #ifndef IGNITION_MSGS_POINTCLOUDPACKEDUTILS_HH_
22 #define IGNITION_MSGS_POINTCLOUDPACKEDUTILS_HH_
23 
25 
26 #include <cstdarg>
27 #include <sstream>
28 #include <string>
29 #include <vector>
30 
31 #include "ignition/msgs/config.hh"
32 #include "ignition/msgs/detail/PointCloudPackedUtils.hh"
33 
34 namespace ignition
35 {
36 namespace msgs
37 {
67 template<typename FieldType>
69  : public PointCloudPackedIteratorBase<
70  FieldType, FieldType, char, PointCloudPacked, PointCloudPackedIterator>
71 {
72  // Documentation inherited
74  const std::string &_fieldName)
75  : PointCloudPackedIteratorBase<FieldType, FieldType, char,
77  ::PointCloudPackedIteratorBase(_cloudMsg, _fieldName)
78  {
79  }
80 };
81 
84 template<typename FieldType>
86  : public PointCloudPackedIteratorBase<
87  FieldType, const FieldType, const char, const PointCloudPacked,
88  PointCloudPackedConstIterator>
89 {
91  const PointCloudPacked &_cloudMsg,
92  const std::string &_fieldName)
93  : PointCloudPackedIteratorBase<FieldType, const FieldType, const char,
94  const PointCloudPacked,
96  >::PointCloudPackedIteratorBase(_cloudMsg, _fieldName)
97  {
98  }
99 };
100 
106 inline int sizeOfPointField(
108 {
109  if ((_dataType == PointCloudPacked::Field::INT8) ||
110  (_dataType == PointCloudPacked::Field::UINT8))
111  {
112  return 1;
113  }
114  else if ((_dataType == PointCloudPacked::Field::INT16) ||
115  (_dataType == PointCloudPacked::Field::UINT16))
116  {
117  return 2;
118  }
119  else if ((_dataType == PointCloudPacked::Field::INT32) ||
120  (_dataType == PointCloudPacked::Field::UINT32) ||
121  (_dataType == PointCloudPacked::Field::FLOAT32))
122  {
123  return 4;
124  }
125  else if (_dataType == PointCloudPacked::Field::FLOAT64)
126  {
127  return 8;
128  }
129  else
130  {
131  std::cerr << "PointCloudPacked::Field of type [" << _dataType
132  << "] does not exist" << std::endl;
133  }
134  return -1;
135 }
136 }
137 }
138 
139 #endif
static const DataType UINT16
Definition: pointcloud_packed.pb.h:150
static const DataType UINT32
Definition: pointcloud_packed.pb.h:154
T endl(T... args)
PointCloudPackedConstIterator(const PointCloudPacked &_cloudMsg, const std::string &_fieldName)
Definition: PointCloudPackedUtils.hh:90
PointCloudPackedIterator(PointCloudPacked &_cloudMsg, const std::string &_fieldName)
Definition: PointCloudPackedUtils.hh:73
STL class.
static const DataType FLOAT64
Definition: pointcloud_packed.pb.h:158
static const DataType INT8
Definition: pointcloud_packed.pb.h:144
static const DataType INT16
Definition: pointcloud_packed.pb.h:148
PointCloudPacked_Field_DataType
Definition: pointcloud_packed.pb.h:56
Class that can iterate over a PointCloudPacked message.
Definition: PointCloudPackedUtils.hh:68
Definition: pointcloud_packed.pb.h:231
static const DataType FLOAT32
Definition: pointcloud_packed.pb.h:156
int sizeOfPointField(PointCloudPacked::Field::DataType _dataType)
Return the size of a datatype (which is an enum of PointCloudPacked::Field) in bytes.
Definition: PointCloudPackedUtils.hh:106
Same as a PointCloudPackedIterator but for const data.
Definition: PointCloudPackedUtils.hh:85
static const DataType INT32
Definition: pointcloud_packed.pb.h:152
static const DataType UINT8
Definition: pointcloud_packed.pb.h:146