ardupilot/libraries/AP_Math/AP_Math.cpp
Andrew Tridgell 1a32ececb4 AP_Math: added a safe_asin() function
this adds range checking to asin()
2012-02-24 11:52:55 +11:00

19 lines
315 B
C++

#include "AP_Math.h"
// a varient of asin() that checks the input ranges and ensures a
// valid angle as output. If nan is given as input then zero is
// returned.
float safe_asin(float v)
{
if (isnan(v)) {
return 0;
}
if (v >= 1.0) {
return PI/2;
}
if (v <= -1.0) {
return -PI/2;
}
return asin(v);
}