point_cloud2_iterator.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Open Source Robotics Foundation
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Source Robotics Foundation nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
36 #define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
37 
38 #include <sensor_msgs/PointCloud2.h>
39 #include <cstdarg>
40 #include <string>
41 #include <vector>
42 
100 namespace sensor_msgs
101 {
106 {
107 public:
112  PointCloud2Modifier(PointCloud2& cloud_msg);
113 
117  size_t size() const;
118 
122  void reserve(size_t size);
123 
127  void resize(size_t size);
128 
132  void clear();
133 
151  void setPointCloud2Fields(int n_fields, ...);
152 
163  void setPointCloud2FieldsByString(int n_fields, ...);
164 protected:
166  PointCloud2& cloud_msg_;
167 };
168 
169 namespace impl
170 {
178 template<typename T, typename TT, typename U, typename C, template <typename> class V>
180 {
181 public:
185 
190  PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name);
191 
196  V<T>& operator =(const V<T>& iter);
197 
203  TT& operator [](size_t i) const;
204 
208  TT& operator *() const;
209 
213  V<T>& operator ++();
214 
219  V<T> operator +(int i);
220 
224  V<T>& operator +=(int i);
225 
229  bool operator !=(const V<T>& iter) const;
230 
234  V<T> end() const;
235 
236 private:
242  int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name);
243 
249  TT* data_;
254 };
255 }
256 
280 template<typename T>
281 class PointCloud2Iterator : public impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
282 {
283 public:
284  PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
285  impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2Iterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
286 };
287 
291 template<typename T>
292 class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
293 {
294 public:
295  PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
296  impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, sensor_msgs::PointCloud2ConstIterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
297 };
298 }
299 
301 
302 #endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
Same as a PointCloud2Iterator but for const data.
PointCloud2Modifier(PointCloud2 &cloud_msg)
Default constructor.
void setPointCloud2Fields(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.
PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
Tools for manipulating sensor_msgs.
Class that can iterate over a PointCloud2.
Enables modifying a sensor_msgs::PointCloud2 like a container.
void clear()
remove all T&#39;s from the original sensor_msgs::PointCloud2
void setPointCloud2FieldsByString(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.


sensor_msgs
Author(s): Tully Foote
autogenerated on Thu Jan 14 2021 03:25:16