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
00036
00037
00038
00039 #ifndef PCL_POINT_CLOUD_ITERATOR_HPP_
00040 #define PCL_POINT_CLOUD_ITERATOR_HPP_
00041
00042 #include <pcl/cloud_iterator.h>
00043
00044 namespace pcl
00045 {
00049 template <class PointT>
00050 class DefaultIterator : public CloudIterator<PointT>::Iterator
00051 {
00052 public:
00053 DefaultIterator (PointCloud<PointT>& cloud)
00054 : cloud_ (cloud)
00055 , iterator_ (cloud.begin ())
00056 {
00057 }
00058
00059 ~DefaultIterator ()
00060 {
00061 }
00062
00063 void operator ++ ()
00064 {
00065 ++iterator_;
00066 }
00067
00068 void operator ++ (int)
00069 {
00070 iterator_++;
00071 }
00072
00073 PointT& operator* () const
00074 {
00075 return (*iterator_);
00076 }
00077
00078 PointT* operator-> ()
00079 {
00080 return (&(*iterator_));
00081 }
00082
00083 unsigned getCurrentPointIndex () const
00084 {
00085 return (iterator_ - cloud_.begin ());
00086 }
00087
00088 unsigned getCurrentIndex () const
00089 {
00090 return (iterator_ - cloud_.begin ());
00091 }
00092
00093 size_t size () const
00094 {
00095 return cloud_.size ();
00096 }
00097
00098 void reset ()
00099 {
00100 iterator_ = cloud_.begin ();
00101 }
00102
00103 bool isValid () const
00104 {
00105 return (iterator_ != cloud_.end ());
00106 }
00107 private:
00108 PointCloud<PointT>& cloud_;
00109 typename PointCloud<PointT>::iterator iterator_;
00110 };
00111
00115 template <class PointT>
00116 class IteratorIdx : public CloudIterator<PointT>::Iterator
00117 {
00118 public:
00119 IteratorIdx (PointCloud<PointT>& cloud, const std::vector<int>& indices)
00120 : cloud_ (cloud)
00121 , indices_ (indices)
00122 , iterator_ (indices_.begin ())
00123 {
00124 }
00125
00126 IteratorIdx (PointCloud<PointT>& cloud, const PointIndices& indices)
00127 : cloud_ (cloud)
00128 , indices_ (indices.indices)
00129 , iterator_ (indices_.begin ())
00130 {
00131 }
00132
00133 virtual ~IteratorIdx () {}
00134
00135 void operator ++ ()
00136 {
00137 ++iterator_;
00138 }
00139
00140 void operator ++ (int)
00141 {
00142 iterator_++;
00143 }
00144
00145 PointT& operator* () const
00146 {
00147 return (cloud_.points [*iterator_]);
00148 }
00149
00150 PointT* operator-> ()
00151 {
00152 return (&(cloud_.points [*iterator_]));
00153 }
00154
00155 unsigned getCurrentPointIndex () const
00156 {
00157 return (*iterator_);
00158 }
00159
00160 unsigned getCurrentIndex () const
00161 {
00162 return (iterator_ - indices_.begin ());
00163 }
00164
00165 size_t size () const
00166 {
00167 return indices_.size ();
00168 }
00169
00170 void reset ()
00171 {
00172 iterator_ = indices_.begin ();
00173 }
00174
00175 bool isValid () const
00176 {
00177 return (iterator_ != indices_.end ());
00178 }
00179
00180 private:
00181 PointCloud<PointT>& cloud_;
00182 std::vector<int> indices_;
00183 std::vector<int>::iterator iterator_;
00184 };
00185
00189 template <class PointT>
00190 class ConstCloudIterator<PointT>::DefaultConstIterator : public ConstCloudIterator<PointT>::Iterator
00191 {
00192 public:
00193 DefaultConstIterator (const PointCloud<PointT>& cloud)
00194 : cloud_ (cloud)
00195 , iterator_ (cloud.begin ())
00196 {
00197 }
00198
00199 ~DefaultConstIterator ()
00200 {
00201 }
00202
00203 void operator ++ ()
00204 {
00205 ++iterator_;
00206 }
00207
00208 void operator ++ (int)
00209 {
00210 iterator_++;
00211 }
00212
00213 const PointT& operator* () const
00214 {
00215 return (*iterator_);
00216 }
00217
00218 const PointT* operator-> () const
00219 {
00220 return (&(*iterator_));
00221 }
00222
00223 unsigned getCurrentPointIndex () const
00224 {
00225 return (unsigned (iterator_ - cloud_.begin ()));
00226 }
00227
00228 unsigned getCurrentIndex () const
00229 {
00230 return (unsigned (iterator_ - cloud_.begin ()));
00231 }
00232
00233 size_t size () const
00234 {
00235 return cloud_.size ();
00236 }
00237
00238 void reset ()
00239 {
00240 iterator_ = cloud_.begin ();
00241 }
00242
00243 bool isValid () const
00244 {
00245 return (iterator_ != cloud_.end ());
00246 }
00247 private:
00248 const PointCloud<PointT>& cloud_;
00249 typename PointCloud<PointT>::const_iterator iterator_;
00250 };
00251
00255 template <class PointT>
00256 class ConstCloudIterator<PointT>::ConstIteratorIdx : public ConstCloudIterator<PointT>::Iterator
00257 {
00258 public:
00259 ConstIteratorIdx (const PointCloud<PointT>& cloud,
00260 const std::vector<int>& indices)
00261 : cloud_ (cloud)
00262 , indices_ (indices)
00263 , iterator_ (indices_.begin ())
00264 {
00265 }
00266
00267 ConstIteratorIdx (const PointCloud<PointT>& cloud,
00268 const PointIndices& indices)
00269 : cloud_ (cloud)
00270 , indices_ (indices.indices)
00271 , iterator_ (indices_.begin ())
00272 {
00273 }
00274
00275 virtual ~ConstIteratorIdx () {}
00276
00277 void operator ++ ()
00278 {
00279 ++iterator_;
00280 }
00281
00282 void operator ++ (int)
00283 {
00284 iterator_++;
00285 }
00286
00287 const PointT& operator* () const
00288 {
00289 return (cloud_.points[*iterator_]);
00290 }
00291
00292 const PointT* operator-> () const
00293 {
00294 return (&(cloud_.points [*iterator_]));
00295 }
00296
00297 unsigned getCurrentPointIndex () const
00298 {
00299 return (unsigned (*iterator_));
00300 }
00301
00302 unsigned getCurrentIndex () const
00303 {
00304 return (unsigned (iterator_ - indices_.begin ()));
00305 }
00306
00307 size_t size () const
00308 {
00309 return indices_.size ();
00310 }
00311
00312 void reset ()
00313 {
00314 iterator_ = indices_.begin ();
00315 }
00316
00317 bool isValid () const
00318 {
00319 return (iterator_ != indices_.end ());
00320 }
00321
00322 private:
00323 const PointCloud<PointT>& cloud_;
00324 std::vector<int> indices_;
00325 std::vector<int>::iterator iterator_;
00326 };
00327 }
00328
00330 template <class PointT>
00331 pcl::CloudIterator<PointT>::CloudIterator (PointCloud<PointT>& cloud)
00332 : iterator_ (new DefaultIterator<PointT> (cloud))
00333 {
00334 }
00335
00337 template <class PointT>
00338 pcl::CloudIterator<PointT>::CloudIterator (
00339 PointCloud<PointT>& cloud, const std::vector<int>& indices)
00340 : iterator_ (new IteratorIdx<PointT> (cloud, indices))
00341 {
00342 }
00343
00345 template <class PointT>
00346 pcl::CloudIterator<PointT>::CloudIterator (
00347 PointCloud<PointT>& cloud, const PointIndices& indices)
00348 : iterator_ (new IteratorIdx<PointT> (cloud, indices))
00349 {
00350 }
00351
00353 template <class PointT>
00354 pcl::CloudIterator<PointT>::CloudIterator (
00355 PointCloud<PointT>& cloud, const Correspondences& corrs, bool source)
00356 {
00357 std::vector<int> indices;
00358 indices.reserve (corrs.size ());
00359 if (source)
00360 {
00361 for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt)
00362 indices.push_back (indexIt->index_query);
00363 }
00364 else
00365 {
00366 for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt)
00367 indices.push_back (indexIt->index_match);
00368 }
00369 iterator_ = new IteratorIdx<PointT> (cloud, indices);
00370 }
00371
00373 template <class PointT>
00374 pcl::CloudIterator<PointT>::~CloudIterator ()
00375 {
00376 delete iterator_;
00377 }
00378
00380 template <class PointT> void
00381 pcl::CloudIterator<PointT>::operator ++ ()
00382 {
00383 iterator_->operator++ ();
00384 }
00385
00387 template <class PointT> void
00388 pcl::CloudIterator<PointT>::operator ++ (int)
00389 {
00390 iterator_->operator++ (0);
00391 }
00392
00394 template <class PointT> PointT&
00395 pcl::CloudIterator<PointT>::operator* () const
00396 {
00397 return (iterator_->operator * ());
00398 }
00399
00401 template <class PointT> PointT*
00402 pcl::CloudIterator<PointT>::operator-> () const
00403 {
00404 return (iterator_->operator-> ());
00405 }
00406
00408 template <class PointT> unsigned
00409 pcl::CloudIterator<PointT>::getCurrentPointIndex () const
00410 {
00411 return (iterator_->getCurrentPointIndex ());
00412 }
00413
00415 template <class PointT> unsigned
00416 pcl::CloudIterator<PointT>::getCurrentIndex () const
00417 {
00418 return (iterator_->getCurrentIndex ());
00419 }
00420
00422 template <class PointT> size_t
00423 pcl::CloudIterator<PointT>::size () const
00424 {
00425 return (iterator_->size ());
00426 }
00427
00429 template <class PointT> void
00430 pcl::CloudIterator<PointT>::reset ()
00431 {
00432 iterator_->reset ();
00433 }
00434
00436 template <class PointT> bool
00437 pcl::CloudIterator<PointT>::isValid () const
00438 {
00439 return (iterator_->isValid ());
00440 }
00441
00442
00444 template <class PointT>
00445 pcl::ConstCloudIterator<PointT>::ConstCloudIterator (const PointCloud<PointT>& cloud)
00446 : iterator_ (new typename pcl::ConstCloudIterator<PointT>::DefaultConstIterator (cloud))
00447 {
00448 }
00449
00451 template <class PointT>
00452 pcl::ConstCloudIterator<PointT>::ConstCloudIterator (
00453 const PointCloud<PointT>& cloud, const std::vector<int>& indices)
00454 : iterator_ (new typename pcl::ConstCloudIterator<PointT>::ConstIteratorIdx (cloud, indices))
00455 {
00456 }
00457
00459 template <class PointT>
00460 pcl::ConstCloudIterator<PointT>::ConstCloudIterator (
00461 const PointCloud<PointT>& cloud, const PointIndices& indices)
00462 : iterator_ (new typename pcl::ConstCloudIterator<PointT>::ConstIteratorIdx (cloud, indices))
00463 {
00464 }
00465
00467 template <class PointT>
00468 pcl::ConstCloudIterator<PointT>::ConstCloudIterator (
00469 const PointCloud<PointT>& cloud, const Correspondences& corrs, bool source)
00470 {
00471 std::vector<int> indices;
00472 indices.reserve (corrs.size ());
00473 if (source)
00474 {
00475 for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt)
00476 indices.push_back (indexIt->index_query);
00477 }
00478 else
00479 {
00480 for (typename Correspondences::const_iterator indexIt = corrs.begin (); indexIt != corrs.end (); ++indexIt)
00481 indices.push_back (indexIt->index_match);
00482 }
00483 iterator_ = new typename pcl::ConstCloudIterator<PointT>::ConstIteratorIdx (cloud, indices);
00484 }
00485
00487 template <class PointT>
00488 pcl::ConstCloudIterator<PointT>::~ConstCloudIterator ()
00489 {
00490 delete iterator_;
00491 }
00492
00494 template <class PointT> void
00495 pcl::ConstCloudIterator<PointT>::operator ++ ()
00496 {
00497 iterator_->operator++ ();
00498 }
00499
00501 template <class PointT> void
00502 pcl::ConstCloudIterator<PointT>::operator ++ (int)
00503 {
00504 iterator_->operator++ (0);
00505 }
00506
00508 template <class PointT> const PointT&
00509 pcl::ConstCloudIterator<PointT>::operator* () const
00510 {
00511 return (iterator_->operator * ());
00512 }
00513
00515 template <class PointT> const PointT*
00516 pcl::ConstCloudIterator<PointT>::operator-> () const
00517 {
00518 return (iterator_->operator-> ());
00519 }
00520
00522 template <class PointT> unsigned
00523 pcl::ConstCloudIterator<PointT>::getCurrentPointIndex () const
00524 {
00525 return (iterator_->getCurrentPointIndex ());
00526 }
00527
00529 template <class PointT> unsigned
00530 pcl::ConstCloudIterator<PointT>::getCurrentIndex () const
00531 {
00532 return (iterator_->getCurrentIndex ());
00533 }
00534
00536 template <class PointT> size_t
00537 pcl::ConstCloudIterator<PointT>::size () const
00538 {
00539 return (iterator_->size ());
00540 }
00541
00543 template <class PointT> void
00544 pcl::ConstCloudIterator<PointT>::reset ()
00545 {
00546 iterator_->reset ();
00547 }
00548
00550 template <class PointT> bool
00551 pcl::ConstCloudIterator<PointT>::isValid () const
00552 {
00553 return (iterator_->isValid ());
00554 }
00555
00556 #endif // PCL_POINT_CLOUD_ITERATOR_HPP_
00557