uncrustify libraries/AP_Math/polygon.cpp

This commit is contained in:
uncrustify 2012-08-16 23:20:14 -07:00 committed by Pat Hickey
parent a208fbb2d9
commit b5bee9deff

View File

@ -20,21 +20,21 @@
#include "AP_Math.h" #include "AP_Math.h"
/* /*
The point in polygon algorithm is based on: * The point in polygon algorithm is based on:
http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html * http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html
*/ */
/* /*
Polygon_outside(): test for a point in a polygon * Polygon_outside(): test for a point in a polygon
Input: P = a point, * Input: P = a point,
V[] = vertex points of a polygon V[n+1] with V[n]=V[0] * V[] = vertex points of a polygon V[n+1] with V[n]=V[0]
Return: true if P is outside the polygon * Return: true if P is outside the polygon
*
This does not take account of the curvature of the earth, but we * This does not take account of the curvature of the earth, but we
expect that to be very small over the distances involved in the * expect that to be very small over the distances involved in the
fence boundary * fence boundary
*/ */
bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n) bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n)
{ {
unsigned i, j; unsigned i, j;
@ -49,7 +49,7 @@ bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n)
dy1 = P.y - V[i].y; dy1 = P.y - V[i].y;
dy2 = V[j].y - V[i].y; dy2 = V[j].y - V[i].y;
int8_t dx1s, dx2s, dy1s, dy2s, m1, m2; int8_t dx1s, dx2s, dy1s, dy2s, m1, m2;
#define sign(x) ((x)<0?-1:1) #define sign(x) ((x)<0 ? -1 : 1)
dx1s = sign(dx1); dx1s = sign(dx1);
dx2s = sign(dx2); dx2s = sign(dx2);
dy1s = sign(dy1); dy1s = sign(dy1);
@ -73,17 +73,17 @@ bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n)
} else if ( dx1 * (int64_t)dy2 < dx2 * (int64_t)dy1 ) { } else if ( dx1 * (int64_t)dy2 < dx2 * (int64_t)dy1 ) {
outside = !outside; outside = !outside;
} }
} }
} }
return outside; return outside;
} }
/* /*
check if a polygon is complete. * check if a polygon is complete.
*
We consider a polygon to be complete if we have at least 4 points, * We consider a polygon to be complete if we have at least 4 points,
and the first point is the same as the last point. That is the * and the first point is the same as the last point. That is the
minimum requirement for the Polygon_outside function to work * minimum requirement for the Polygon_outside function to work
*/ */
bool Polygon_complete(const Vector2l *V, unsigned n) bool Polygon_complete(const Vector2l *V, unsigned n)
{ {