Program Listing for File BufferRegion.hpp

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

/*
 * BufferRegion.hpp
 *
 *  Created on: Aug 19, 2015
 *      Author: Péter Fankhauser
 *   Institute: ETH Zurich, ANYbotics
 */

#ifndef GRID_MAP_CORE__BUFFERREGION_HPP_
#define GRID_MAP_CORE__BUFFERREGION_HPP_

#include "grid_map_core/TypeDefs.hpp"

namespace grid_map
{

class BufferRegion
{
public:
  enum class Quadrant
  {
    Undefined,
    TopLeft,
    TopRight,
    BottomLeft,
    BottomRight
  };

  constexpr static unsigned int nQuadrants = 4;

  BufferRegion();
  BufferRegion(
    const Index & startIndex, const Size & size,
    const BufferRegion::Quadrant & quadrant);
  virtual ~BufferRegion() = default;

  const Index & getStartIndex() const;
  void setStartIndex(const Index & startIndex);
  const Size & getSize() const;
  void setSize(const Size & size);
  BufferRegion::Quadrant getQuadrant() const;
  void setQuadrant(BufferRegion::Quadrant type);

private:
  Index staretIndex_;

  Size size_;

  Quadrant quadrant_;

public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

}  // namespace grid_map
#endif  // GRID_MAP_CORE__BUFFERREGION_HPP_