mirror of https://github.com/ArduPilot/ardupilot
AP_Math: correct warning on fabsF
2024-08-08T01:51:53.6780446Z ../../libraries/AP_Math/vector3.cpp:432:9: warning: absolute value function 'fabsf' given an argument of type 'const double' but has parameter of type 'float' which may cause truncation of value [-Wabsolute-value] 2024-08-08T01:51:53.6781336Z if (fabsF(cosv) >= 1) { 2024-08-08T01:51:53.6781583Z ^ 2024-08-08T01:51:53.6781930Z ../../libraries/AP_Math/ftype.h:50:18: note: expanded from macro 'fabsF' 2024-08-08T01:51:53.6782342Z #define fabsF(x) fabsf(x) 2024-08-08T01:51:53.6782572Z ^ 2024-08-08T01:51:53.6789178Z ../../libraries/AP_Math/vector3.cpp:633:16: note: in instantiation of member function 'Vector3<double>::angle' requested here 2024-08-08T01:51:53.6789800Z template class Vector3<double>;
This commit is contained in:
parent
08bf7c6163
commit
6c788c6ae0
|
@ -429,7 +429,7 @@ T Vector3<T>::angle(const Vector3<T> &v2) const
|
||||||
return 0.0f;
|
return 0.0f;
|
||||||
}
|
}
|
||||||
const T cosv = ((*this)*v2) / len;
|
const T cosv = ((*this)*v2) / len;
|
||||||
if (fabsF(cosv) >= 1) {
|
if (cosv >= 1 || cosv <= -1) {
|
||||||
return 0.0f;
|
return 0.0f;
|
||||||
}
|
}
|
||||||
return acosF(cosv);
|
return acosF(cosv);
|
||||||
|
|
Loading…
Reference in New Issue