Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 #pragma once
00010 
00011 #include <grid_map_core/TypeDefs.hpp>
00012 
00013 
00014 #include <vector>
00015 
00016 
00017 #include <Eigen/Core>
00018 
00019 namespace grid_map {
00020 
00021 class Polygon
00022 {
00023  public:
00024 
00025   enum class TriangulationMethods {
00026     FAN 
00027   };
00028 
00032   Polygon();
00033 
00038   Polygon(std::vector<Position> vertices);
00039 
00043   virtual ~Polygon();
00044 
00050   bool isInside(const Position& point) const;
00051 
00056   void addVertex(const Position& vertex);
00057 
00063   const Position& getVertex(const size_t index) const;
00064 
00068   void removeVertices();
00069 
00075   const Position& operator [](const size_t index) const;
00076 
00081   const std::vector<Position>& getVertices() const;
00082 
00087   size_t nVertices() const;
00088 
00093   void setTimestamp(const uint64_t timestamp);
00094 
00099   uint64_t getTimestamp() const;
00100 
00104   void resetTimestamp();
00105 
00110   void setFrameId(const std::string& frameId);
00111 
00116   const std::string& getFrameId() const;
00117 
00123   double getArea() const;
00124 
00130   Position getCentroid() const;
00131 
00137   void getBoundingBox(Position& center, Length& length) const;
00138 
00150   bool convertToInequalityConstraints(Eigen::MatrixXd& A,
00151                                       Eigen::VectorXd& b) const;
00152 
00159   bool offsetInward(const double margin);
00160 
00167   bool thickenLine(const double thickness);
00168 
00173   std::vector<Polygon> triangulate(const TriangulationMethods& method = TriangulationMethods::FAN) const;
00174 
00182   static Polygon fromCircle(const Position center, const double radius,
00183                             const int nVertices = 20);
00184 
00193   static Polygon convexHullOfTwoCircles(const Position center1,
00194                                         const Position center2,
00195                                         const double radius,
00196                                         const int nVertices = 20);
00197 
00204   static Polygon convexHull(Polygon& polygon1, Polygon& polygon2);
00205 
00211   static Polygon monotoneChainConvexHullOfPoints(const std::vector<Position>& points);
00212 
00213  protected:
00214 
00220   static bool sortVertices(const Eigen::Vector2d& vector1,
00221                            const Eigen::Vector2d& vector2);
00222 
00228   static double computeCrossProduct2D(const Eigen::Vector2d& vector1,
00229                                       const Eigen::Vector2d& vector2);
00230 
00237   static double vectorsMakeClockwiseTurn(const Eigen::Vector2d& pointO,
00238                                          const Eigen::Vector2d& pointA,
00239                                          const Eigen::Vector2d& pointB);
00240 
00242   std::string frameId_;
00243 
00245   uint64_t timestamp_;
00246 
00248   std::vector<Position> vertices_;
00249 
00250  public:
00251   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00252 };
00253 
00254 }