AP_Math.h 7.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284
  1. #pragma once
  2. #include <cmath>
  3. #include <limits>
  4. #include <stdint.h>
  5. #include <type_traits>
  6. #include <AP_Common/AP_Common.h>
  7. #include <AP_Param/AP_Param.h>
  8. #include "definitions.h"
  9. #include "crc.h"
  10. #include "matrix3.h"
  11. #include "polygon.h"
  12. #include "quaternion.h"
  13. #include "rotations.h"
  14. #include "vector2.h"
  15. #include "vector3.h"
  16. #include "spline5.h"
  17. #include "location.h"
  18. #include "vector4.h"
  19. #include "matrix4.h"
  20. // define AP_Param types AP_Vector3f and Ap_Matrix3f
  21. AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
  22. /*
  23. * Check whether two floats are equal
  24. */
  25. template <typename Arithmetic1, typename Arithmetic2>
  26. typename std::enable_if<std::is_integral<typename std::common_type<Arithmetic1, Arithmetic2>::type>::value ,bool>::type
  27. is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2);
  28. template <typename Arithmetic1, typename Arithmetic2>
  29. typename std::enable_if<std::is_floating_point<typename std::common_type<Arithmetic1, Arithmetic2>::type>::value, bool>::type
  30. is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2);
  31. /*
  32. * @brief: Check whether a float is zero
  33. */
  34. template <typename T>
  35. inline bool is_zero(const T fVal1) {
  36. static_assert(std::is_floating_point<T>::value || std::is_base_of<T,AP_Float>::value,
  37. "Template parameter not of type float");
  38. return (fabsf(static_cast<float>(fVal1)) < FLT_EPSILON);
  39. }
  40. /*
  41. * @brief: Check whether a float is greater than zero
  42. */
  43. template <typename T>
  44. inline bool is_positive(const T fVal1) {
  45. static_assert(std::is_floating_point<T>::value || std::is_base_of<T,AP_Float>::value,
  46. "Template parameter not of type float");
  47. return (static_cast<float>(fVal1) >= FLT_EPSILON);
  48. }
  49. /*
  50. * @brief: Check whether a float is less than zero
  51. */
  52. template <typename T>
  53. inline bool is_negative(const T fVal1) {
  54. static_assert(std::is_floating_point<T>::value || std::is_base_of<T,AP_Float>::value,
  55. "Template parameter not of type float");
  56. return (static_cast<float>(fVal1) <= (-1.0 * FLT_EPSILON));
  57. }
  58. /*
  59. * A variant of asin() that checks the input ranges and ensures a valid angle
  60. * as output. If nan is given as input then zero is returned.
  61. */
  62. template <typename T>
  63. float safe_asin(const T v);
  64. /*
  65. * A variant of sqrt() that checks the input ranges and ensures a valid value
  66. * as output. If a negative number is given then 0 is returned. The reasoning
  67. * is that a negative number for sqrt() in our code is usually caused by small
  68. * numerical rounding errors, so the real input should have been zero
  69. */
  70. template <typename T>
  71. float safe_sqrt(const T v);
  72. // invOut is an inverted 4x4 matrix when returns true, otherwise matrix is Singular
  73. bool inverse3x3(float m[], float invOut[]) WARN_IF_UNUSED;
  74. // invOut is an inverted 3x3 matrix when returns true, otherwise matrix is Singular
  75. bool inverse4x4(float m[],float invOut[]) WARN_IF_UNUSED;
  76. // matrix multiplication of two NxN matrices
  77. float *mat_mul(float *A, float *B, uint8_t n);
  78. // matrix algebra
  79. bool inverse(float x[], float y[], uint16_t dim) WARN_IF_UNUSED;
  80. /*
  81. * Constrain an angle to be within the range: -180 to 180 degrees. The second
  82. * parameter changes the units. Default: 1 == degrees, 10 == dezi,
  83. * 100 == centi.
  84. */
  85. template <typename T>
  86. float wrap_180(const T angle, float unit_mod = 1);
  87. /*
  88. * Wrap an angle in centi-degrees. See wrap_180().
  89. */
  90. template <typename T>
  91. auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f));
  92. /*
  93. * Constrain an euler angle to be within the range: 0 to 360 degrees. The
  94. * second parameter changes the units. Default: 1 == degrees, 10 == dezi,
  95. * 100 == centi.
  96. */
  97. template <typename T>
  98. float wrap_360(const T angle, float unit_mod = 1);
  99. /*
  100. * Wrap an angle in centi-degrees. See wrap_360().
  101. */
  102. template <typename T>
  103. auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f));
  104. /*
  105. wrap an angle in radians to -PI ~ PI (equivalent to +- 180 degrees)
  106. */
  107. template <typename T>
  108. float wrap_PI(const T radian);
  109. /*
  110. * wrap an angle in radians to 0..2PI
  111. */
  112. template <typename T>
  113. float wrap_2PI(const T radian);
  114. /*
  115. * Constrain a value to be within the range: low and high
  116. */
  117. template <typename T>
  118. T constrain_value(const T amt, const T low, const T high);
  119. inline float constrain_float(const float amt, const float low, const float high)
  120. {
  121. return constrain_value(amt, low, high);
  122. }
  123. inline int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
  124. {
  125. return constrain_value(amt, low, high);
  126. }
  127. inline int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
  128. {
  129. return constrain_value(amt, low, high);
  130. }
  131. inline int64_t constrain_int64(const int64_t amt, const int64_t low, const int64_t high)
  132. {
  133. return constrain_value(amt, low, high);
  134. }
  135. // degrees -> radians
  136. static inline constexpr float radians(float deg)
  137. {
  138. return deg * DEG_TO_RAD;
  139. }
  140. // radians -> degrees
  141. static inline constexpr float degrees(float rad)
  142. {
  143. return rad * RAD_TO_DEG;
  144. }
  145. template<typename T>
  146. float sq(const T val)
  147. {
  148. float v = static_cast<float>(val);
  149. return v*v;
  150. }
  151. /*
  152. * Variadic template for calculating the square norm of a vector of any
  153. * dimension.
  154. */
  155. template<typename T, typename... Params>
  156. float sq(const T first, const Params... parameters)
  157. {
  158. return sq(first) + sq(parameters...);
  159. }
  160. /*
  161. * Variadic template for calculating the norm (pythagoras) of a vector of any
  162. * dimension.
  163. */
  164. template<typename T, typename U, typename... Params>
  165. float norm(const T first, const U second, const Params... parameters)
  166. {
  167. return sqrtf(sq(first, second, parameters...));
  168. }
  169. template<typename A, typename B>
  170. static inline auto MIN(const A &one, const B &two) -> decltype(one < two ? one : two)
  171. {
  172. return one < two ? one : two;
  173. }
  174. template<typename A, typename B>
  175. static inline auto MAX(const A &one, const B &two) -> decltype(one > two ? one : two)
  176. {
  177. return one > two ? one : two;
  178. }
  179. inline uint32_t hz_to_nsec(uint32_t freq)
  180. {
  181. return AP_NSEC_PER_SEC / freq;
  182. }
  183. inline uint32_t nsec_to_hz(uint32_t nsec)
  184. {
  185. return AP_NSEC_PER_SEC / nsec;
  186. }
  187. inline uint32_t usec_to_nsec(uint32_t usec)
  188. {
  189. return usec * AP_NSEC_PER_USEC;
  190. }
  191. inline uint32_t nsec_to_usec(uint32_t nsec)
  192. {
  193. return nsec / AP_NSEC_PER_USEC;
  194. }
  195. inline uint32_t hz_to_usec(uint32_t freq)
  196. {
  197. return AP_USEC_PER_SEC / freq;
  198. }
  199. inline uint32_t usec_to_hz(uint32_t usec)
  200. {
  201. return AP_USEC_PER_SEC / usec;
  202. }
  203. /*
  204. linear interpolation based on a variable in a range
  205. */
  206. float linear_interpolate(float low_output, float high_output,
  207. float var_value,
  208. float var_low, float var_high);
  209. /* cubic "expo" curve generator
  210. * alpha range: [0,1] min to max expo
  211. * input range: [-1,1]
  212. */
  213. float expo_curve(float alpha, float input);
  214. /* throttle curve generator
  215. * thr_mid: output at mid stick
  216. * alpha: expo coefficient
  217. * thr_in: [0-1]
  218. */
  219. float throttle_curve(float thr_mid, float alpha, float thr_in);
  220. /* simple 16 bit random number generator */
  221. uint16_t get_random16(void);
  222. // generate a random float between -1 and 1, for use in SITL
  223. float rand_float(void);
  224. // generate a random Vector3f of size 1
  225. Vector3f rand_vec3f(void);
  226. // confirm a value is a valid octal value
  227. bool is_valid_octal(uint16_t octal) WARN_IF_UNUSED;
  228. // return true if two rotations are equal
  229. bool rotation_equal(enum Rotation r1, enum Rotation r2) WARN_IF_UNUSED;
  230. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  231. // fill an array of float with NaN, used to invalidate memory in SITL
  232. void fill_nanf(float *f, uint16_t count);
  233. #endif