mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Math: buidl fix for templates
This commit is contained in:
parent
4f9ad370a3
commit
ce6dcacb11
@ -118,6 +118,26 @@ bool Polygon_complete(const Vector2<T> *V, unsigned n)
|
||||
return (n >= 4 && V[n-1] == V[0]);
|
||||
}
|
||||
|
||||
/*
|
||||
return the closest distance that point p comes to an edge of closed
|
||||
polygon V, defined by N points
|
||||
*/
|
||||
template <typename T>
|
||||
float Polygon_closest_distance_point(const Vector2<T> *V, unsigned N, const Vector2<T> &p)
|
||||
{
|
||||
T closest_sq = std::numeric_limits<T>::max();
|
||||
for (uint8_t i=0; i<N-1; i++) {
|
||||
const Vector2<T> &v1 = V[i];
|
||||
const Vector2<T> &v2 = V[i+1];
|
||||
|
||||
T dist_sq = Vector2<T>::closest_distance_between_line_and_point_squared(v1, v2, p);
|
||||
if (dist_sq < closest_sq) {
|
||||
closest_sq = dist_sq;
|
||||
}
|
||||
}
|
||||
return sqrtF(closest_sq);
|
||||
}
|
||||
|
||||
// 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);
|
||||
@ -196,23 +216,3 @@ float Polygon_closest_distance_line(const Vector2f *V, unsigned N, const Vector2
|
||||
}
|
||||
return sqrtf(closest_sq);
|
||||
}
|
||||
|
||||
/*
|
||||
return the closest distance that point p comes to an edge of closed
|
||||
polygon V, defined by N points
|
||||
*/
|
||||
template <typename T>
|
||||
float Polygon_closest_distance_point(const Vector2<T> *V, unsigned N, const Vector2<T> &p)
|
||||
{
|
||||
T closest_sq = std::numeric_limits<T>::max();
|
||||
for (uint8_t i=0; i<N-1; i++) {
|
||||
const Vector2<T> &v1 = V[i];
|
||||
const Vector2<T> &v2 = V[i+1];
|
||||
|
||||
T dist_sq = Vector2<T>::closest_distance_between_line_and_point_squared(v1, v2, p);
|
||||
if (dist_sq < closest_sq) {
|
||||
closest_sq = dist_sq;
|
||||
}
|
||||
}
|
||||
return sqrtf(closest_sq);
|
||||
}
|
||||
|
@ -20,13 +20,6 @@
|
||||
|
||||
#include "AP_Math.h"
|
||||
|
||||
template float Vector2f::closest_distance_between_line_and_point_squared(const Vector2f &w1,
|
||||
const Vector2f &w2,
|
||||
const Vector2f &p);
|
||||
template int32_t Vector2l::closest_distance_between_line_and_point_squared(const Vector2l &w1,
|
||||
const Vector2l &w2,
|
||||
const Vector2l &p);
|
||||
|
||||
template <typename T>
|
||||
T Vector2<T>::length_squared() const
|
||||
{
|
||||
@ -464,4 +457,4 @@ template bool Vector2<long>::operator ==(const Vector2<long> &v) const;
|
||||
template bool Vector2<long>::operator !=(const Vector2<long> &v) const;
|
||||
template bool Vector2<int>::operator ==(const Vector2<int> &v) const;
|
||||
template bool Vector2<int>::operator !=(const Vector2<int> &v) const;
|
||||
|
||||
template int Vector2<int>::closest_distance_between_line_and_point_squared(Vector2<int> const&, Vector2<int> const&, Vector2<int> const&);
|
||||
|
Loading…
Reference in New Issue
Block a user