mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Math: prevent a floating point exception
This commit is contained in:
parent
4d24a86088
commit
7e5a491f14
@ -125,7 +125,15 @@ bool Vector2<T>::operator !=(const Vector2<T> &v) const
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
float Vector2<T>::angle(const Vector2<T> &v2) const
|
float Vector2<T>::angle(const Vector2<T> &v2) const
|
||||||
{
|
{
|
||||||
return acosf(((*this)*v2) / (this->length()*v2.length()));
|
float len = this->length() * v2.length();
|
||||||
|
if (len <= 0) {
|
||||||
|
return 0.0f;
|
||||||
|
}
|
||||||
|
float cosv = ((*this)*v2) / len;
|
||||||
|
if (fabsf(cosv) >= 1) {
|
||||||
|
return 0.0f;
|
||||||
|
}
|
||||||
|
return acosf(cosv);
|
||||||
}
|
}
|
||||||
|
|
||||||
// only define for float
|
// only define for float
|
||||||
|
Loading…
Reference in New Issue
Block a user