APM:Libraries
AP_Math.cpp
Go to the documentation of this file.
1 #include "AP_Math.h"
2 
3 #include <float.h>
4 
5 /*
6  * is_equal(): Integer implementation, provided for convenience and
7  * compatibility with old code. Expands to the same as comparing the values
8  * directly
9  */
10 template <typename Arithmetic1, typename Arithmetic2>
11 typename std::enable_if<std::is_integral<typename std::common_type<Arithmetic1, Arithmetic2>::type>::value ,bool>::type
12 is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
13 {
14  typedef typename std::common_type<Arithmetic1, Arithmetic2>::type common_type;
15  return static_cast<common_type>(v_1) == static_cast<common_type>(v_2);
16 }
17 
18 /*
19  * is_equal(): double/float implementation - takes into account
20  * std::numeric_limits<T>::epsilon() to return if 2 values are equal.
21  */
22 template <typename Arithmetic1, typename Arithmetic2>
23 typename std::enable_if<std::is_floating_point<typename std::common_type<Arithmetic1, Arithmetic2>::type>::value, bool>::type
24 is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
25 {
26 #ifdef ALLOW_DOUBLE_MATH_FUNCTIONS
27  typedef typename std::common_type<Arithmetic1, Arithmetic2>::type common_type;
28  typedef typename std::remove_cv<common_type>::type common_type_nonconst;
30  return fabs(v_1 - v_2) < std::numeric_limits<double>::epsilon();
31  }
32 #endif
33  return fabsf(v_1 - v_2) < std::numeric_limits<float>::epsilon();
34 }
35 
36 template bool is_equal<int>(const int v_1, const int v_2);
37 template bool is_equal<short>(const short v_1, const short v_2);
38 template bool is_equal<long>(const long v_1, const long v_2);
39 template bool is_equal<float>(const float v_1, const float v_2);
40 template bool is_equal<double>(const double v_1, const double v_2);
41 
42 template <typename T>
43 float safe_asin(const T v)
44 {
45  const float f = static_cast<const float>(v);
46  if (isnan(f)) {
47  return 0.0f;
48  }
49  if (f >= 1.0f) {
50  return static_cast<float>(M_PI_2);
51  }
52  if (f <= -1.0f) {
53  return static_cast<float>(-M_PI_2);
54  }
55  return asinf(f);
56 }
57 
58 template float safe_asin<int>(const int v);
59 template float safe_asin<short>(const short v);
60 template float safe_asin<float>(const float v);
61 template float safe_asin<double>(const double v);
62 
63 template <typename T>
64 float safe_sqrt(const T v)
65 {
66  float ret = sqrtf(static_cast<float>(v));
67  if (isnan(ret)) {
68  return 0;
69  }
70  return ret;
71 }
72 
73 template float safe_sqrt<int>(const int v);
74 template float safe_sqrt<short>(const short v);
75 template float safe_sqrt<float>(const float v);
76 template float safe_sqrt<double>(const double v);
77 
78 /*
79  linear interpolation based on a variable in a range
80  */
81 float linear_interpolate(float low_output, float high_output,
82  float var_value,
83  float var_low, float var_high)
84 {
85  if (var_value <= var_low) {
86  return low_output;
87  }
88  if (var_value >= var_high) {
89  return high_output;
90  }
91  float p = (var_value - var_low) / (var_high - var_low);
92  return low_output + p * (high_output - low_output);
93 }
94 
95 template <typename T>
96 float wrap_180(const T angle, float unit_mod)
97 {
98  auto res = wrap_360(angle, unit_mod);
99  if (res > 180.f * unit_mod) {
100  res -= 360.f * unit_mod;
101  }
102  return res;
103 }
104 
105 template float wrap_180<int>(const int angle, float unit_mod);
106 template float wrap_180<short>(const short angle, float unit_mod);
107 template float wrap_180<float>(const float angle, float unit_mod);
108 template float wrap_180<double>(const double angle, float unit_mod);
109 
110 template <typename T>
111 auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
112 {
113  return wrap_180(angle, 100.f);
114 }
115 
116 template auto wrap_180_cd<float>(const float angle) -> decltype(wrap_180(angle, 100.f));
117 template auto wrap_180_cd<int>(const int angle) -> decltype(wrap_180(angle, 100.f));
118 template auto wrap_180_cd<long>(const long angle) -> decltype(wrap_180(angle, 100.f));
119 template auto wrap_180_cd<short>(const short angle) -> decltype(wrap_180(angle, 100.f));
120 template auto wrap_180_cd<double>(const double angle) -> decltype(wrap_360(angle, 100.f));
121 
122 template <typename T>
123 float wrap_360(const T angle, float unit_mod)
124 {
125  const float ang_360 = 360.f * unit_mod;
126  float res = fmodf(static_cast<float>(angle), ang_360);
127  if (res < 0) {
128  res += ang_360;
129  }
130  return res;
131 }
132 
133 template float wrap_360<int>(const int angle, float unit_mod);
134 template float wrap_360<short>(const short angle, float unit_mod);
135 template float wrap_360<long>(const long angle, float unit_mod);
136 template float wrap_360<float>(const float angle, float unit_mod);
137 template float wrap_360<double>(const double angle, float unit_mod);
138 
139 template <typename T>
140 auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
141 {
142  return wrap_360(angle, 100.f);
143 }
144 
145 template auto wrap_360_cd<float>(const float angle) -> decltype(wrap_360(angle, 100.f));
146 template auto wrap_360_cd<int>(const int angle) -> decltype(wrap_360(angle, 100.f));
147 template auto wrap_360_cd<long>(const long angle) -> decltype(wrap_360(angle, 100.f));
148 template auto wrap_360_cd<short>(const short angle) -> decltype(wrap_360(angle, 100.f));
149 template auto wrap_360_cd<double>(const double angle) -> decltype(wrap_360(angle, 100.f));
150 
151 template <typename T>
152 float wrap_PI(const T radian)
153 {
154  auto res = wrap_2PI(radian);
155  if (res > M_PI) {
156  res -= M_2PI;
157  }
158  return res;
159 }
160 
161 template float wrap_PI<int>(const int radian);
162 template float wrap_PI<short>(const short radian);
163 template float wrap_PI<float>(const float radian);
164 template float wrap_PI<double>(const double radian);
165 
166 template <typename T>
167 float wrap_2PI(const T radian)
168 {
169  float res = fmodf(static_cast<float>(radian), M_2PI);
170  if (res < 0) {
171  res += M_2PI;
172  }
173  return res;
174 }
175 
176 template float wrap_2PI<int>(const int radian);
177 template float wrap_2PI<short>(const short radian);
178 template float wrap_2PI<float>(const float radian);
179 template float wrap_2PI<double>(const double radian);
180 
181 template <typename T>
182 T constrain_value(const T amt, const T low, const T high)
183 {
184  // the check for NaN as a float prevents propagation of floating point
185  // errors through any function that uses constrain_value(). The normal
186  // float semantics already handle -Inf and +Inf
187  if (isnan(amt)) {
188  return (low + high) / 2;
189  }
190 
191  if (amt < low) {
192  return low;
193  }
194 
195  if (amt > high) {
196  return high;
197  }
198 
199  return amt;
200 }
201 
202 template int constrain_value<int>(const int amt, const int low, const int high);
203 template long constrain_value<long>(const long amt, const long low, const long high);
204 template short constrain_value<short>(const short amt, const short low, const short high);
205 template float constrain_value<float>(const float amt, const float low, const float high);
206 template double constrain_value<double>(const double amt, const double low, const double high);
207 
208 
209 /*
210  simple 16 bit random number generator
211  */
212 uint16_t get_random16(void)
213 {
214  static uint32_t m_z = 1234;
215  static uint32_t m_w = 76542;
216  m_z = 36969 * (m_z & 0xFFFFu) + (m_z >> 16);
217  m_w = 18000 * (m_w & 0xFFFFu) + (m_w >> 16);
218  return ((m_z << 16) + m_w) & 0xFFFF;
219 }
220 
221 
222 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
223 // generate a random float between -1 and 1, for use in SITL
224 float rand_float(void)
225 {
226  return ((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6;
227 }
228 
230 {
232  rand_float(),
233  rand_float());
234  if (v.length() != 0.0f) {
235  v.normalize();
236  }
237  return v;
238 }
239 #endif
240 
241 bool is_valid_octal(uint16_t octal)
242 {
243  // treat "octal" as decimal and test if any decimal digit is > 7
244  if (octal > 7777) {
245  return false;
246  } else if (octal % 10 > 7) {
247  return false;
248  } else if ((octal % 100)/10 > 7) {
249  return false;
250  } else if ((octal % 1000)/100 > 7) {
251  return false;
252  } else if ((octal % 10000)/1000 > 7) {
253  return false;
254  }
255  return true;
256 }
template double constrain_value< double >(const double amt, const double low, const double high)
template float wrap_2PI< float >(const float radian)
template float safe_sqrt< float >(const float v)
Vector3< float > Vector3f
Definition: vector3.h:246
#define M_PI_2
Definition: definitions.h:15
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
template float safe_asin< double >(const double v)
template float safe_sqrt< short >(const short v)
template float wrap_PI< int >(const int radian)
template float wrap_180< short >(const short angle, float unit_mod)
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
Definition: AP_Math.cpp:140
template auto wrap_180_cd< int >(const int angle) -> decltype(wrap_180(angle, 100.f))
template float safe_asin< int >(const int v)
template auto wrap_180_cd< double >(const double angle) -> decltype(wrap_360(angle, 100.f))
bool is_valid_octal(uint16_t octal)
Definition: AP_Math.cpp:241
template float wrap_2PI< short >(const short radian)
template float safe_asin< short >(const short v)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
template bool is_equal< double >(const double v_1, const double v_2)
template float constrain_value< float >(const float amt, const float low, const float high)
template float wrap_360< double >(const double angle, float unit_mod)
uint16_t get_random16(void)
Definition: AP_Math.cpp:212
template auto wrap_360_cd< double >(const double angle) -> decltype(wrap_360(angle, 100.f))
template float safe_sqrt< double >(const double v)
template float wrap_360< float >(const float angle, float unit_mod)
template auto wrap_360_cd< short >(const short angle) -> decltype(wrap_360(angle, 100.f))
template bool is_equal< float >(const float v_1, const float v_2)
float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high)
Definition: AP_Math.cpp:81
float wrap_180(const T angle, float unit_mod)
Definition: AP_Math.cpp:96
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
template long constrain_value< long >(const long amt, const long low, const long high)
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
template float safe_sqrt< int >(const int v)
template float wrap_360< int >(const int angle, float unit_mod)
#define f(i)
template float wrap_180< float >(const float angle, float unit_mod)
template float wrap_PI< double >(const double radian)
template float safe_asin< float >(const float v)
template auto wrap_360_cd< int >(const int angle) -> decltype(wrap_360(angle, 100.f))
#define M_2PI
Definition: definitions.h:19
float v
Definition: Printf.cpp:15
template float wrap_PI< short >(const short radian)
template float wrap_360< short >(const short angle, float unit_mod)
void normalize()
Definition: vector3.h:176
template float wrap_360< long >(const long angle, float unit_mod)
float safe_asin(const T v)
Definition: AP_Math.cpp:43
float length(void) const
Definition: vector3.cpp:288
template auto wrap_180_cd< long >(const long 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_360_cd< float >(const float angle) -> decltype(wrap_360(angle, 100.f))
template short constrain_value< short >(const short amt, const short low, const short high)
float wrap_2PI(const T radian)
Definition: AP_Math.cpp:167
template bool is_equal< short >(const short v_1, const short v_2)
template float wrap_2PI< int >(const int radian)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
template auto wrap_360_cd< long >(const long angle) -> decltype(wrap_360(angle, 100.f))
float rand_float(void)
Definition: AP_Math.cpp:224
template auto wrap_180_cd< float >(const float angle) -> decltype(wrap_180(angle, 100.f))
template float wrap_PI< float >(const float radian)
float value
Vector3f rand_vec3f(void)
Definition: AP_Math.cpp:229
template float wrap_180< double >(const double angle, float unit_mod)
#define M_PI
Definition: definitions.h:10
template float wrap_2PI< double >(const double radian)
template float wrap_180< int >(const int angle, float unit_mod)
template int constrain_value< int >(const int amt, const int low, const int high)
template bool is_equal< long >(const long v_1, const long v_2)
template bool is_equal< int >(const int v_1, const int v_2)
T constrain_value(const T amt, const T low, const T high)
Definition: AP_Math.cpp:182