Class Polygon
Defined in File Polygon.hpp
Class Documentation
-
class Polygon
-
Public Functions
-
Polygon()
Default constructor.
-
explicit Polygon(std::vector<Position> vertices)
Constructor with vertices.
- Parameters:
vertices – the points of the polygon.
-
virtual ~Polygon() = default
Destructor.
-
bool isInside(const Position &point) const
Check if point is inside polygon.
- Parameters:
point – the point to be checked.
- Returns:
true if inside, false otherwise.
-
void addVertex(const Position &vertex)
Add a vertex to the polygon
- Parameters:
vertex – the point to be added.
-
const Position &getVertex(const size_t index) const
Get the vertex with index.
- Parameters:
index – the index of the requested vertex.
- Returns:
the requested vertex.
-
void removeVertices()
Removes all vertices from the polygon.
-
const Position &operator[](const size_t index) const
Get vertex operator overload.
- Parameters:
index – the index of the requested vertex.
- Returns:
the requested vertex.
-
const std::vector<Position> &getVertices() const
Returns the vertices of the polygon.
- Returns:
the vertices of the polygon.
-
size_t nVertices() const
Returns the number of vertices.
- Returns:
the number of vertices.
-
void setTimestamp(const uint64_t timestamp)
Set the timestamp of the polygon.
- Parameters:
timestamp – the timestamp to set (in nanoseconds).
-
uint64_t getTimestamp() const
Get the timestamp of the polygon.
- Returns:
timestamp in nanoseconds.
-
void resetTimestamp()
Resets the timestamp of the polygon (to zero).
-
void setFrameId(const std::string &frameId)
Set the frame id of the polygon.
- Parameters:
frameId – the frame id to set.
-
const std::string &getFrameId() const
Get the frameId of the polygon.
- Returns:
frameId.
-
double getArea() const
Get the area of the polygon. The polygon has to be “simple”, i.e. not crossing itself.
- Returns:
area of the polygon.
-
Position getCentroid() const
Get the centroid of polygon. The polygon has to be “simple”, i.e. not crossing itself.
- Returns:
centroid of polygon.
-
void getBoundingBox(Position ¢er, Length &length) const
Gets the bounding box of the polygon.
- Parameters:
center – the center of the bounding box.
length – the side lengths of the bounding box.
-
bool convertToInequalityConstraints(Eigen::MatrixXd &A, Eigen::VectorXd &b) const
Convert polygon to inequality constraints which most tightly contain the points; i.e., create constraints to bound the convex hull of polygon. The inequality constraints are represented as A and b, a set of constraints such that A*x <= b defining the region of space enclosing the convex hull. Based on the VERT2CON MATLAB method by Michael Kleder: http://www.mathworks.com/matlabcentral/fileexchange/7895-vert2con-vertices-to-constraints
- Parameters:
A – the A matrix in of the inequality constraint.
b – the b matrix in of the inequality constraint.
- Returns:
true if conversion successful, false otherwise.
-
bool offsetInward(const double margin)
Offsets the polygon inward (buffering) by a margin. Use a negative margin to offset the polygon outward.
- Parameters:
margin – the margin to offset the polygon by (in [m]).
- Returns:
true if successful, false otherwise.
-
bool thickenLine(const double thickness)
If only two verices are given, this methods generates a
thickened
line polygon with four vertices.- Parameters:
thickness – the desired thickness of the line.
- Returns:
true if successful, false otherwise.
-
std::vector<Polygon> triangulate(const TriangulationMethods &method = TriangulationMethods::FAN) const
Return a triangulated version of the polygon.
- Returns:
a list of triangle polygons covering the same polygon.
Public Static Functions
-
static Polygon fromCircle(const Position center, const double radius, const int nVertices = 20)
Approximates a circle with a polygon.
- Parameters:
center – [in] the center position of the circle.
radius – [in] radius of the circle.
nVertices – [in] number of vertices of the approximation polygon. Default = 20.
- Returns:
circle as polygon.
-
static Polygon convexHullOfTwoCircles(const Position center1, const Position center2, const double radius, const int nVertices = 20)
Approximates two circles with a convex hull and returns it as polygon.
- Parameters:
center1 – [in] the center position of the first circle.
center2 – [in] the center position of the second circle.
radius – [in] radius of the circles.
nVertices – [in] number of vertices of the approximation polygon. Default = 20.
- Returns:
convex hull of the two circles as polygon.
-
static Polygon convexHull(Polygon &polygon1, Polygon &polygon2)
Computes the convex hull of two polygons and returns it as polygon.
- Parameters:
polygon1 – [in] the first input polygon.
polygon2 – [in] the second input polygon.
- Returns:
convex hull as polygon.
-
static Polygon monotoneChainConvexHullOfPoints(const std::vector<Position> &points)
Computes the convex hull of given points, using Andrew’s monotone chain convex hull algorithm, and returns it as polygon.
- Parameters:
points – [in] points to use to compute the convex hull used to create the polygon.
- Returns:
convex hull as polygon.
Protected Attributes
-
std::string frameId_
Frame id of the polygon.
-
uint64_t timestamp_
Timestamp of the polygon (nanoseconds).
Protected Static Functions
-
static bool sortVertices(const Eigen::Vector2d &vector1, const Eigen::Vector2d &vector2)
Returns true if the vector1 and vector2 are sorted lexicographically.
- Parameters:
vector1 – [in] the first input vector.
vector2 – [in] the second input vector.
-
static double computeCrossProduct2D(const Eigen::Vector2d &vector1, const Eigen::Vector2d &vector2)
Returns the 2D cross product of vector1 and vector2.
- Parameters:
vector1 – [in] the first input vector.
vector2 – [in] the second input vector.
-
static double vectorsMakeClockwiseTurn(const Eigen::Vector2d &pointO, const Eigen::Vector2d &pointA, const Eigen::Vector2d &pointB)
Returns true if OAB makes a clockwise turn or if the OA and OB vectors are collinear.
- Parameters:
pointO – [in] point of the origin O, used to compute OA and OB.
pointA – [in] input point A, used to compute OA.
pointB – [in] input point B, used to compute OB.
-
Polygon()