point_cloud2_iterator.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
37 #define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
38 
40 #include <cstdarg>
41 #include <string>
42 #include <vector>
43 
101 namespace sensor_msgs
102 {
106 class PointCloud2Modifier
107 {
108 public:
113  PointCloud2Modifier(PointCloud2& cloud_msg);
114 
118  size_t size() const;
119 
123  void reserve(size_t size);
124 
128  void resize(size_t size);
129 
133  void clear();
134 
152  void setPointCloud2Fields(int n_fields, ...);
153 
164  void setPointCloud2FieldsByString(int n_fields, ...);
165 protected:
168 };
169 
170 namespace impl
171 {
179 template<typename T, typename TT, typename U, typename C, template <typename> class V>
180 class PointCloud2IteratorBase
181 {
182 public:
186 
191  PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name);
192 
197  V<T>& operator =(const V<T>& iter);
198 
204  TT& operator [](size_t i) const;
205 
209  TT& operator *() const;
210 
214  V<T>& operator ++();
215 
220  V<T> operator +(int i);
221 
225  V<T>& operator +=(int i);
226 
230  bool operator !=(const V<T>& iter) const;
231 
235  V<T> end() const;
236 
237 private:
243  int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name);
244 
246  int point_step_;
248  U* data_char_;
250  TT* data_;
252  TT* data_end_;
254  bool is_bigendian_;
255 };
256 }
257 
281 template<typename T>
282 class PointCloud2Iterator : public impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
283 {
284 public:
285  PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
287 };
288 
292 template<typename T>
293 class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
294 {
295 public:
296  PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
298 };
299 }
300 
302 
303 #endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
sensor_msgs::impl::PointCloud2IteratorBase::operator=
V< T > & operator=(const V< T > &iter)
Definition: impl/point_cloud2_iterator.h:262
point_cloud2_iterator.h
sensor_msgs::impl::PointCloud2IteratorBase::operator[]
TT & operator[](size_t i) const
Definition: impl/point_cloud2_iterator.h:282
sensor_msgs::impl::PointCloud2IteratorBase::data_
TT * data_
Definition: point_cloud2_iterator.h:250
sensor_msgs::impl::PointCloud2IteratorBase::end
V< T > end() const
Definition: impl/point_cloud2_iterator.h:346
sensor_msgs::PointCloud2Modifier::reserve
void reserve(size_t size)
Definition: impl/point_cloud2_iterator.h:111
sensor_msgs::PointCloud2Modifier::PointCloud2Modifier
PointCloud2Modifier(PointCloud2 &cloud_msg)
Definition: impl/point_cloud2_iterator.h:102
sensor_msgs::PointCloud2Modifier::size
size_t size() const
Definition: impl/point_cloud2_iterator.h:106
sensor_msgs::PointCloud2
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
Definition: PointCloud2.h:90
sensor_msgs::impl::PointCloud2IteratorBase::point_step_
int point_step_
Definition: point_cloud2_iterator.h:246
sensor_msgs::impl::PointCloud2IteratorBase::operator+=
V< T > & operator+=(int i)
Definition: impl/point_cloud2_iterator.h:326
sensor_msgs::impl::PointCloud2IteratorBase::operator!=
bool operator!=(const V< T > &iter) const
Definition: impl/point_cloud2_iterator.h:337
sensor_msgs::PointCloud2Modifier::setPointCloud2Fields
void setPointCloud2Fields(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.
Definition: impl/point_cloud2_iterator.h:166
sensor_msgs::PointCloud2Iterator::PointCloud2Iterator
PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
sensor_msgs::impl::PointCloud2IteratorBase::data_end_
TT * data_end_
Definition: point_cloud2_iterator.h:252
sensor_msgs::impl::PointCloud2IteratorBase::is_bigendian_
bool is_bigendian_
Definition: point_cloud2_iterator.h:254
sensor_msgs::impl::PointCloud2IteratorBase::PointCloud2IteratorBase
PointCloud2IteratorBase()
Definition: impl/point_cloud2_iterator.h:239
PointCloud2.h
sensor_msgs::impl::PointCloud2IteratorBase::operator*
TT & operator*() const
Definition: impl/point_cloud2_iterator.h:291
sensor_msgs::PointCloud2Modifier::cloud_msg_
PointCloud2 & cloud_msg_
Definition: point_cloud2_iterator.h:167
sensor_msgs::PointCloud2_
Definition: PointCloud2.h:25
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
Definition: impl/point_cloud2_iterator.h:116
sensor_msgs::impl::PointCloud2IteratorBase::set_field
int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
Definition: impl/point_cloud2_iterator.h:359
sensor_msgs::impl::PointCloud2IteratorBase::operator+
V< T > operator+(int i)
Definition: impl/point_cloud2_iterator.h:312
sick_scan_base.h
sensor_msgs::PointCloud2Modifier::clear
void clear()
Definition: impl/point_cloud2_iterator.h:134
sensor_msgs::impl::PointCloud2IteratorBase::data_char_
U * data_char_
Definition: point_cloud2_iterator.h:248
sensor_msgs
Tools for manipulating sensor_msgs.
sensor_msgs::PointCloud2ConstIterator::PointCloud2ConstIterator
PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.
Definition: impl/point_cloud2_iterator.h:198
sensor_msgs::impl::PointCloud2IteratorBase::operator++
V< T > & operator++()
Definition: impl/point_cloud2_iterator.h:300


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09