mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
1a32ececb4
this adds range checking to asin()
19 lines
315 B
C++
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);
|
|
}
|