Program Listing for File GridMapIterator.hpp

Return to documentation for file (/tmp/ws/src/grid_map/grid_map_core/include/grid_map_core/iterators/GridMapIterator.hpp)

/*
 * GridMapIterator.hpp
 *
 *  Created on: Sep 22, 2014
 *      Author: Péter Fankhauser
 *   Institute: ETH Zurich, ANYbotics
 */
#ifndef GRID_MAP_CORE__ITERATORS__GRIDMAPITERATOR_HPP_
#define GRID_MAP_CORE__ITERATORS__GRIDMAPITERATOR_HPP_

#include <Eigen/Core>

#include "grid_map_core/GridMap.hpp"

namespace grid_map
{

class GridMapIterator
{
public:
  explicit GridMapIterator(const grid_map::GridMap & gridMap);

  explicit GridMapIterator(const GridMapIterator * other);

  GridMapIterator & operator=(const GridMapIterator & other);

  bool operator!=(const GridMapIterator & other) const;

  const Index operator*() const;

  const size_t & getLinearIndex() const;

  const Index getUnwrappedIndex() const;

  virtual GridMapIterator & operator++();

  GridMapIterator end() const;

  bool isPastEnd() const;

protected:
  Size size_;

  Index startIndex_;

  size_t linearSize_;

  size_t linearIndex_;

  bool isPastEnd_;

public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

}  // namespace grid_map

#endif  // GRID_MAP_CORE__ITERATORS__GRIDMAPITERATOR_HPP_