mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: correct Polygon_outside floating point instatiation
This routine was entemplatificated from the integer version, which was designed to be perfect across representable ranges of points. The floating point version suffered from a rounding problem.
This commit is contained in:
parent
b35b65eed1
commit
51a0401383
@ -59,16 +59,32 @@ bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n)
|
||||
outside = !outside;
|
||||
} else if (m1 < m2) {
|
||||
continue;
|
||||
} else if ( dx1 * (int64_t)dy2 > dx2 * (int64_t)dy1 ) {
|
||||
outside = !outside;
|
||||
} else {
|
||||
if (std::is_floating_point<T>::value) {
|
||||
if ( dx1 * dy2 > dx2 * dy1 ) {
|
||||
outside = !outside;
|
||||
}
|
||||
} else {
|
||||
if ( dx1 * (int64_t)dy2 > dx2 * (int64_t)dy1 ) {
|
||||
outside = !outside;
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (m1 < m2) {
|
||||
outside = !outside;
|
||||
} else if (m1 > m2) {
|
||||
continue;
|
||||
} else if ( dx1 * (int64_t)dy2 < dx2 * (int64_t)dy1 ) {
|
||||
outside = !outside;
|
||||
} else {
|
||||
if (std::is_floating_point<T>::value) {
|
||||
if ( dx1 * dy2 < dx2 * dy1 ) {
|
||||
outside = !outside;
|
||||
}
|
||||
} else {
|
||||
if ( dx1 * (int64_t)dy2 < dx2 * (int64_t)dy1 ) {
|
||||
outside = !outside;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user