ardupilot/libraries/AP_Math/AP_Math.cpp

134 lines
3.9 KiB
C++
Raw Normal View History

#include "AP_Math.h"
#include <float.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.0f;
}
if (v >= 1.0f) {
return M_PI/2;
}
if (v <= -1.0f) {
return -M_PI/2;
}
return asinf(v);
}
// a varient of sqrt() that checks the input ranges and ensures a
// valid value as output. If a negative number is given then 0 is
// returned. The reasoning is that a negative number for sqrt() in our
// code is usually caused by small numerical rounding errors, so the
// real input should have been zero
float safe_sqrt(float v)
{
float ret = sqrtf(v);
if (isnan(ret)) {
return 0;
}
return ret;
}
/*
linear interpolation based on a variable in a range
*/
float linear_interpolate(float low_output, float high_output,
float var_value,
float var_low, float var_high)
{
if (var_value <= var_low) {
return low_output;
}
if (var_value >= var_high) {
return high_output;
}
float p = (var_value - var_low) / (var_high - var_low);
return low_output + p * (high_output - low_output);
}
template <class T>
float wrap_180(const T angle, float unit_mod)
{
auto res = wrap_360(angle, unit_mod);
if (res > 180.f * unit_mod) {
res -= 360.f * unit_mod;
}
return res;
}
template float wrap_180<int>(const int angle, float unit_mod);
template float wrap_180<short>(const short angle, float unit_mod);
template float wrap_180<float>(const float angle, float unit_mod);
template float wrap_180<double>(const double angle, float unit_mod);
template <class T>
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
{
return wrap_180(angle, 100.f);
}
template auto wrap_180_cd<float>(const float angle) -> decltype(wrap_180(angle, 100.f));
template auto wrap_180_cd<int>(const int angle) -> decltype(wrap_180(angle, 100.f));
template auto wrap_180_cd<short>(const short angle) -> decltype(wrap_180(angle, 100.f));
template auto wrap_180_cd<double>(const double angle) -> decltype(wrap_360(angle, 100.f));
template <class T>
float wrap_360(const T angle, float unit_mod)
{
const float ang_360 = 360.f * unit_mod;
float res = fmodf(static_cast<float>(angle), ang_360);
if (res < 0) {
res += ang_360;
}
return res;
}
template float wrap_360<int>(const int angle, float unit_mod);
template float wrap_360<short>(const short angle, float unit_mod);
template float wrap_360<float>(const float angle, float unit_mod);
template float wrap_360<double>(const double angle, float unit_mod);
template <class T>
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
{
return wrap_360(angle, 100.f);
}
template auto wrap_360_cd<float>(const float angle) -> decltype(wrap_360(angle, 100.f));
template auto wrap_360_cd<int>(const int angle) -> decltype(wrap_360(angle, 100.f));
template auto wrap_360_cd<short>(const short angle) -> decltype(wrap_360(angle, 100.f));
template auto wrap_360_cd<double>(const double angle) -> decltype(wrap_360(angle, 100.f));
template <class T>
float wrap_PI(const T radian)
{
auto res = wrap_2PI(radian);
if (res > M_PI) {
res -= M_2PI;
}
return res;
}
template float wrap_PI<int>(const int radian);
template float wrap_PI<short>(const short radian);
template float wrap_PI<float>(const float radian);
template float wrap_PI<double>(const double radian);
template <class T>
float wrap_2PI(const T radian)
{
float res = fmodf(static_cast<float>(radian), M_2PI);
if (res < 0) {
res += M_2PI;
}
return res;
}
template float wrap_2PI<int>(const int radian);
template float wrap_2PI<short>(const short radian);
template float wrap_2PI<float>(const float radian);
template float wrap_2PI<double>(const double radian);