Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
00036 #define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
00037
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <cstdarg>
00040 #include <string>
00041 #include <vector>
00042
00100 namespace sensor_msgs
00101 {
00105 class PointCloud2Modifier
00106 {
00107 public:
00112 PointCloud2Modifier(PointCloud2& cloud_msg);
00113
00117 size_t size() const;
00118
00122 void reserve(size_t size);
00123
00127 void resize(size_t size);
00128
00132 void clear();
00133
00151 void setPointCloud2Fields(int n_fields, ...);
00152
00163 void setPointCloud2FieldsByString(int n_fields, ...);
00164 protected:
00166 PointCloud2& cloud_msg_;
00167 };
00168
00169 namespace impl
00170 {
00178 template<typename T, typename TT, typename U, typename C, template <typename> class V>
00179 class PointCloud2IteratorBase
00180 {
00181 public:
00184 PointCloud2IteratorBase();
00185
00190 PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name);
00191
00196 V<T>& operator =(const V<T>& iter);
00197
00203 TT& operator [](size_t i) const;
00204
00208 TT& operator *() const;
00209
00213 V<T>& operator ++();
00214
00219 V<T> operator +(int i);
00220
00224 V<T>& operator +=(int i);
00225
00229 bool operator !=(const V<T>& iter) const;
00230
00234 V<T> end() const;
00235
00236 private:
00242 int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name);
00243
00245 int point_step_;
00247 U* data_char_;
00249 TT* data_;
00251 TT* data_end_;
00253 bool is_bigendian_;
00254 };
00255 }
00256
00280 template<typename T>
00281 class PointCloud2Iterator : public impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
00282 {
00283 public:
00284 PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
00285 impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2Iterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
00286 };
00287
00291 template<typename T>
00292 class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
00293 {
00294 public:
00295 PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
00296 impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, sensor_msgs::PointCloud2ConstIterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
00297 };
00298 }
00299
00300 #include <sensor_msgs/impl/point_cloud2_iterator.h>
00301
00302 #endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H