mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: add Polygon_outside and Polygon_complete functions
This commit is contained in:
parent
80bda572ba
commit
249d95b413
@ -35,7 +35,8 @@
|
||||
* expect that to be very small over the distances involved in the
|
||||
* fence boundary
|
||||
*/
|
||||
bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n)
|
||||
template <typename T>
|
||||
bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n)
|
||||
{
|
||||
unsigned i, j;
|
||||
bool outside = true;
|
||||
@ -85,7 +86,14 @@ bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n)
|
||||
* and the first point is the same as the last point. That is the
|
||||
* minimum requirement for the Polygon_outside function to work
|
||||
*/
|
||||
bool Polygon_complete(const Vector2l *V, unsigned n)
|
||||
template <typename T>
|
||||
bool Polygon_complete(const Vector2<T> *V, unsigned n)
|
||||
{
|
||||
return (n >= 4 && V[n-1].x == V[0].x && V[n-1].y == V[0].y);
|
||||
}
|
||||
|
||||
// Necessary to avoid linker errors
|
||||
template bool Polygon_outside<int32_t>(const Vector2l &P, const Vector2l *V, unsigned n);
|
||||
template bool Polygon_complete<int32_t>(const Vector2l *V, unsigned n);
|
||||
template bool Polygon_outside<float>(const Vector2f &P, const Vector2f *V, unsigned n);
|
||||
template bool Polygon_complete<float>(const Vector2f *V, unsigned n);
|
||||
|
@ -20,6 +20,8 @@
|
||||
|
||||
#include "vector2.h"
|
||||
|
||||
bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n);
|
||||
bool Polygon_complete(const Vector2l *V, unsigned n);
|
||||
template <typename T>
|
||||
bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n);
|
||||
template <typename T>
|
||||
bool Polygon_complete(const Vector2<T> *V, unsigned n);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user