74 base_class::insert(base_class::end(), other.begin(), other.end());
96 for (size_type i = 0; i < size() - 1; ++i)
98 result += at(i).getX() * at(i + 1).getY() - at(i + 1).getX() * at(i).getY();
102 result += at(size() - 1).getX() * at(0).getY() - at(0).getX() * at(size() - 1).getY();
105 return std::abs(0.5 * result);
114 return centerOfGravity;
117 for (Polygon2D::const_iterator edgeIter = begin(); edgeIter != end(); ++edgeIter)
119 centerOfGravity += *edgeIter;
122 centerOfGravity /= size();
124 return centerOfGravity;
129 return !empty() && (front() == back());
140 const Circle2D circle(center, radius);
156 if (result.size() > 1)
157 result.back() = result.front();
164 const UINT32 samplingPoints,
const bool clockwise)
169 if (clockwise ==
true)
172 while (startAngle < end)
180 while (end < startAngle)
186 return fromArc(ellipse, startAngle, end, samplingPoints);
191 const UINT32 samplingPoints)
196 if (samplingPoints < 2)
202 if (fabs(endAngle - startAngle) >
double(2.0 * M_PI + 1e-3))
204 throw std::invalid_argument(
"Polygon2D::fromArc: Angle difference is too large! Is " + ::
toString(fabs(endAngle - startAngle), 2) +
" but must be at most 2*pi.");
212 for (
UINT32 p = 0 ; p < samplingPoints; p++)
215 if (p == (samplingPoints - 1))
224 polygon.push_back(point);
233 return "()[],; \t\"'";
284 Polygon2D::const_iterator iter = begin();
291 for ( ; iter != end(); ++iter)
295 if (x < minX) minX = x;
296 if (x > maxX) maxX = x;
297 if (y < minY) minY = y;
298 if (y > maxY) maxY = y;
300 return Box2D(0.5 * (maxX + minX),
309 return std::make_pair(0, 0);
319 return std::make_pair(-
PI,
PI);
325 Polygon2D::const_iterator iter = begin();
329 bool gotPointOnNegativeX =
false;
330 for ( ; iter != end(); ++iter)
333 && (iter->getX() < 0.0))
338 gotPointOnNegativeX =
true;
344 if (pointangle < minangle)
345 minangle = pointangle;
347 if (pointangle > maxangle)
348 maxangle = pointangle;
355 if (gotPointOnNegativeX)
357 if (std::max(minangle, maxangle) <= 0.0f)
359 else if (std::min(minangle, maxangle) >= 0.0f)
368 return std::make_pair(minangle, maxangle);
443 bool isInside(
false);
448 for (i = 0; i < size(); j = i++)
451 ( (p[i].getY() > point.
getY()) != (p[j].getY() > point.
getY()) )
453 ( point.
getX() < ( (p[j].getX() - p[i].getX())
454 * (point.
getY() - p[i].getY())
455 / (p[j].getY() - p[i].getY())
459 isInside = !isInside;
469 min = max = (axis * polygon[0]);
471 for (Polygon2D::const_iterator edge = polygon.begin(); edge != polygon.end(); ++edge)
474 min = std::min(min, dotProduct);
475 max = std::max(max, dotProduct);
495 both.reserve(both.size() + p2.size());
496 both.insert(both.end(), p2.begin(), p2.end());
498 for (Polygon2D::const_iterator edge = both.begin(); edge != both.end(); ++edge)
500 Point2D axis(-edge->getY(), edge->getX());
520 if (size() < 2 || other.
isZero())
524 for (
size_t k = 1; k < size(); ++k)
527 Line2D currentline(
operator[](k - 1),
operator[](k));
530 result.push_back(isect);
538 return empty() ? 0 : point.
dist(front());
542 for (
size_t k = 1; k < size(); ++k)
544 Line2D line(
operator[](k - 1),
operator[](k));
557 result.reserve(size());
560 result.push_back(front());
562 for (size_type k = 1; k < size() - 1; ++k)
564 const Point2D& previous = result.back();
565 const Point2D& current = operator[](k);
566 const Point2D& next = operator[](k + 1);
567 Line2D line(previous, next);
572 result.push_back(current);
576 result.push_back(back());
586 std::string text =
"[ ";
587 if (empty() ==
false)
589 for (size_type k = 0; k < size(); k++)
591 const Point2D& current = operator[](k);
std::string toString(UINT16 digits=2) const
Text output for debugging.
bool isColliding(const Polygon2D &p2) const
Returns true if the given polygon collides with this polygon.
const Point2D & getCenter() const
Returns the center point of this Ellipse.
static Polygon2D createRectangle(const Point2D &lowerLeft, const Point2D &upperRight)
std::string toString() const
Text output for debugging.
bool containsPoint(const Point2D &point) const
Returns true if the given Point2D is inside this polygon.
A rotated 2-dimensional box in the plane.
Point2D getCenterOfGravity() const
Returns the center of gravity of this polygon.
Box2D getBoundingBox() const
Returns a Box in parallel to the coordinate system that bounds this polygon.
Polygon2D getSimplified() const
Returns a polygon with potentially less edge points.
Point2D::value_type floatingpoint_type
Polygon2D()
Constructor for an empty polygon.
std::pair< floatingpoint_type, floatingpoint_type > getBoundingAngles() const
value_type getRotation() const
static Polygon2D rhombus(const Point2D ¢er, const floatingpoint_type radius)
Static function to create a rhombus.
bool containsPoint(const Point2D &point) const
Returns true if this line "contains" the given point.
Polygon2D & append(const Polygon2D &other)
Appends the points of the other polygon to this polygon.
Polygon2D::floatingpoint_type intervalDistance(const Polygon2D::floatingpoint_type minA, const Polygon2D::floatingpoint_type maxA, const Polygon2D::floatingpoint_type minB, const Polygon2D::floatingpoint_type maxB)
bool isClosed() const
Returns true if this is explicitly a closed polygon.
static Polygon2D fromArc(const Ellipse2D &ellipse, const floatingpoint_type startAngle, const floatingpoint_type endAngle, const UINT32 samplingPoints, const bool clockwise)
(DEPRECATED) Create a Polygon2D approximation of the arc of an ellipse
void projectOntoAxis(const Point2D &axis, const Polygon2D &polygon, Polygon2D::floatingpoint_type &min, Polygon2D::floatingpoint_type &max)
base_class isIntersecting(const Line2D &other) const
Calculates all intersection points between a line and this polygon.
A line in the two-dimensional plane, composed out of two points.
double value_type
The type of the stored x and y coordinates.
double distanceFromLineSegment(const Point2D &point) const
Returns the distance of a point to this line segment.
static Polygon2D fromEllipse(const Point2D ¢er, const floatingpoint_type a, const floatingpoint_type b, const floatingpoint_type angle, const UINT32 samplingPoints=32)
Static function to create a Polygon2D from ellipse parameters.
static Polygon2D fromCircle(const Point2D ¢er, const floatingpoint_type radius, const UINT32 samplingPoints=32)
Static function to get Polygon2D from circle parameters.
A rotated 2-dimensional ellipse in the plane.
static const char * getSeparatorCharacters()
bool isZero() const
Returns true if both points are zero.
IntersectingType isIntersecting(const Line2D &other, Point2D *intersectingPoint=NULL) const
Calculates the intersection point between two lines.
Point2D::value_type distanceToPoint(const Point2D &point) const
Returns the distance of a point to this polyon.
The lines are intersecting within their line segments.
std::vector< Point2D > base_class
The base type. (Naming according to boost convention.)
const Point2D & getRadius() const
Returns the radius of this Ellipse.
double getArea() const
Returns the area enclosed by this polygon.