Program Listing for File EllipseIterator.hpp

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

/*
 * EllipseIterator.hpp
 *
 *  Created on: Dec 2, 2015
 *      Author: Péter Fankhauser
 *   Institute: ETH Zurich, ANYbotics
 */
#ifndef GRID_MAP_CORE__ITERATORS__ELLIPSEITERATOR_HPP_
#define GRID_MAP_CORE__ITERATORS__ELLIPSEITERATOR_HPP_

#include <Eigen/Core>
#include <memory>

#include "grid_map_core/GridMap.hpp"
#include "grid_map_core/iterators/SubmapIterator.hpp"

namespace grid_map
{

class EllipseIterator
{
public:
  EllipseIterator(
    const GridMap & gridMap, const Position & center, const Length & length,
    const double rotation = 0.0);

  EllipseIterator & operator=(const EllipseIterator & other);

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

  const Index & operator*() const;

  EllipseIterator & operator++();

  bool isPastEnd() const;

  const Size & getSubmapSize() const;

private:
  bool isInside() const;

  void findSubmapParameters(
    const Position & center, const Length & length, const double rotation,
    Index & startIndex, Size & bufferSize) const;

  Position center_;

  Eigen::Array2d semiAxisSquare_;

  Eigen::Matrix2d transformMatrix_;

  std::shared_ptr<SubmapIterator> internalIterator_;

  Length mapLength_;
  Position mapPosition_;
  double resolution_;
  Size bufferSize_;
  Index bufferStartIndex_;

public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

}  // namespace grid_map
#endif  // GRID_MAP_CORE__ITERATORS__ELLIPSEITERATOR_HPP_