test_math.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305
  1. // given we are in the Math library, you're epected to know what
  2. // you're doing when directly comparing floats:
  3. #pragma GCC diagnostic push
  4. #pragma GCC diagnostic ignored "-Wfloat-equal"
  5. #include <AP_gtest.h>
  6. #include <AP_Math/AP_Math.h>
  7. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  8. #define SQRT_2 1.4142135623730951f
  9. TEST(VectorTest, Rotations)
  10. {
  11. unsigned rotation_count = 0;
  12. #define TEST_ROTATION(rotation, _x, _y, _z) { \
  13. const float accuracy = 1.0e-6; \
  14. Vector3f v(1, 1, 1); \
  15. v.rotate(rotation); \
  16. Vector3f expected(_x, _y, _z); \
  17. EXPECT_NEAR(expected.length(), v.length(), accuracy); \
  18. EXPECT_FLOAT_EQ(expected.x, v.x); \
  19. EXPECT_FLOAT_EQ(expected.y, v.y); \
  20. EXPECT_FLOAT_EQ(expected.z, v.z); \
  21. rotation_count++; \
  22. }
  23. TEST_ROTATION(ROTATION_NONE, 1, 1, 1);
  24. TEST_ROTATION(ROTATION_YAW_45, 0, SQRT_2, 1);
  25. TEST_ROTATION(ROTATION_YAW_90, -1, 1, 1);
  26. TEST_ROTATION(ROTATION_YAW_135, -SQRT_2, 0, 1);
  27. TEST_ROTATION(ROTATION_YAW_180, -1, -1, 1);
  28. TEST_ROTATION(ROTATION_YAW_225, 0, -SQRT_2, 1);
  29. TEST_ROTATION(ROTATION_YAW_270, 1, -1, 1);
  30. TEST_ROTATION(ROTATION_YAW_315, SQRT_2, 0, 1);
  31. TEST_ROTATION(ROTATION_ROLL_180, 1, -1, -1);
  32. TEST_ROTATION(ROTATION_ROLL_180_YAW_45, SQRT_2, 0, -1);
  33. TEST_ROTATION(ROTATION_ROLL_180_YAW_90, 1, 1, -1);
  34. TEST_ROTATION(ROTATION_ROLL_180_YAW_135, 0, SQRT_2, -1);
  35. TEST_ROTATION(ROTATION_PITCH_180, -1, 1, -1);
  36. TEST_ROTATION(ROTATION_ROLL_180_YAW_225, -SQRT_2, 0, -1);
  37. TEST_ROTATION(ROTATION_ROLL_180_YAW_270, -1, -1, -1);
  38. TEST_ROTATION(ROTATION_ROLL_180_YAW_315, 0, -SQRT_2, -1);
  39. TEST_ROTATION(ROTATION_ROLL_90, 1, -1, 1);
  40. TEST_ROTATION(ROTATION_ROLL_90_YAW_45, SQRT_2, 0, 1);
  41. TEST_ROTATION(ROTATION_ROLL_90_YAW_90, 1, 1, 1);
  42. TEST_ROTATION(ROTATION_ROLL_90_YAW_135, 0, SQRT_2, 1);
  43. TEST_ROTATION(ROTATION_ROLL_270, 1, 1, -1);
  44. TEST_ROTATION(ROTATION_ROLL_270_YAW_45, 0, SQRT_2, -1);
  45. TEST_ROTATION(ROTATION_ROLL_270_YAW_90, -1, 1, -1);
  46. TEST_ROTATION(ROTATION_ROLL_270_YAW_135, -SQRT_2, 0, -1);
  47. TEST_ROTATION(ROTATION_PITCH_90, 1, 1, -1);
  48. TEST_ROTATION(ROTATION_PITCH_270, -1, 1, 1);
  49. TEST_ROTATION(ROTATION_PITCH_180_YAW_90, -1, -1, -1);
  50. TEST_ROTATION(ROTATION_PITCH_180_YAW_270, 1, 1, -1);
  51. TEST_ROTATION(ROTATION_ROLL_90_PITCH_90, 1, -1, -1);
  52. TEST_ROTATION(ROTATION_ROLL_180_PITCH_90, -1, -1, -1);
  53. TEST_ROTATION(ROTATION_ROLL_270_PITCH_90, -1, 1, -1);
  54. TEST_ROTATION(ROTATION_ROLL_90_PITCH_180, -1, -1, -1);
  55. TEST_ROTATION(ROTATION_ROLL_270_PITCH_180, -1, 1, 1);
  56. TEST_ROTATION(ROTATION_ROLL_90_PITCH_270, -1, -1, 1);
  57. TEST_ROTATION(ROTATION_ROLL_180_PITCH_270, 1, -1, 1);
  58. TEST_ROTATION(ROTATION_ROLL_270_PITCH_270, 1, 1, 1);
  59. TEST_ROTATION(ROTATION_ROLL_90_PITCH_180_YAW_90, 1, -1, -1);
  60. TEST_ROTATION(ROTATION_ROLL_90_YAW_270, -1, -1, 1);
  61. TEST_ROTATION(ROTATION_ROLL_90_PITCH_68_YAW_293, -0.4066309f, -1.5839677f, -0.5706992f);
  62. TEST_ROTATION(ROTATION_PITCH_315, 0, 1, SQRT_2);
  63. TEST_ROTATION(ROTATION_ROLL_90_PITCH_315, 0, -1, SQRT_2);
  64. TEST_ROTATION(ROTATION_PITCH_7, 1.1144155f, 1, 0.87067682f);
  65. EXPECT_EQ(ROTATION_MAX, rotation_count) << "All rotations are expect to be tested";
  66. }
  67. TEST(MathTest, IsZero)
  68. {
  69. EXPECT_FALSE(is_zero(0.1));
  70. EXPECT_FALSE(is_zero(0.0001));
  71. EXPECT_TRUE(is_zero(0.f));
  72. EXPECT_TRUE(is_zero(FLT_MIN));
  73. EXPECT_TRUE(is_zero(-FLT_MIN));
  74. }
  75. TEST(MathTest, IsEqual)
  76. {
  77. EXPECT_FALSE(is_equal(1, 0));
  78. EXPECT_TRUE(is_equal(1, 1));
  79. EXPECT_FALSE(is_equal(0.1, 0.10001));
  80. EXPECT_FALSE(is_equal(0.1, -0.1001));
  81. EXPECT_TRUE(is_equal(0.f, 0.0f));
  82. EXPECT_FALSE(is_equal(1.f, 1.f + FLT_EPSILON));
  83. EXPECT_TRUE(is_equal(1.f, 1.f + FLT_EPSILON / 2.f));
  84. EXPECT_TRUE(is_equal(1.f, (float)(1.f - DBL_EPSILON)));
  85. // false because the common type is double
  86. EXPECT_FALSE(is_equal(double(1.), 1 + 2 * std::numeric_limits<double>::epsilon()));
  87. // true because the common type is float
  88. EXPECT_TRUE(is_equal(1.f, (float)(1. + std::numeric_limits<double>::epsilon())));
  89. }
  90. TEST(MathTest, Square)
  91. {
  92. float sq_0 = sq(0);
  93. float sq_1 = sq(1);
  94. float sq_2 = sq(2);
  95. EXPECT_EQ(0.f, sq_0);
  96. EXPECT_EQ(1.f, sq_1);
  97. EXPECT_EQ(4.f, sq_2);
  98. }
  99. TEST(MathTest, Norm)
  100. {
  101. float norm_1 = norm(1, 4.2);
  102. float norm_2 = norm(1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1);
  103. float norm_3 = norm(0, 5.3);
  104. float norm_4 = norm(0,0,0,0,0,0,0,0,0,0,0,0,0,0,0);
  105. float norm_5 = norm(3,4);
  106. float norm_6 = norm(4,3,12);
  107. EXPECT_FLOAT_EQ(norm_1, 4.3174066f);
  108. EXPECT_EQ(norm_2, 4.f);
  109. EXPECT_EQ(norm_3, 5.3f);
  110. EXPECT_EQ(norm_4, 0.f);
  111. EXPECT_EQ(norm_5, 5.f);
  112. EXPECT_EQ(norm_6, 13.f);
  113. }
  114. TEST(MathTest, Constrain)
  115. {
  116. for (int i = 0; i < 1000; i++) {
  117. if (i < 250) {
  118. EXPECT_EQ(250, constrain_float(i, 250, 500));
  119. EXPECT_EQ(250, constrain_int16(i, 250, 500));
  120. EXPECT_EQ(250, constrain_int32(i, 250, 500));
  121. EXPECT_EQ(250, constrain_int64(i, 250, 500));
  122. } else if (i > 500) {
  123. EXPECT_EQ(500, constrain_float(i, 250, 500));
  124. EXPECT_EQ(500, constrain_int16(i, 250, 500));
  125. EXPECT_EQ(500, constrain_int32(i, 250, 500));
  126. EXPECT_EQ(500, constrain_int64(i, 250, 500));
  127. } else {
  128. EXPECT_EQ(i, constrain_float(i, 250, 500));
  129. EXPECT_EQ(i, constrain_int16(i, 250, 500));
  130. EXPECT_EQ(i, constrain_int32(i, 250, 500));
  131. EXPECT_EQ(i, constrain_int64(i, 250, 500));
  132. }
  133. }
  134. for (int i = 0; i <= 1000; i++) {
  135. int c = i - 1000;
  136. if (c < -250) {
  137. EXPECT_EQ(-250, constrain_float(c, -250, -50));
  138. EXPECT_EQ(-250, constrain_int16(c, -250, -50));
  139. EXPECT_EQ(-250, constrain_int32(c, -250, -50));
  140. EXPECT_EQ(-250, constrain_int64(c, -250, -50));
  141. } else if(c > -50) {
  142. EXPECT_EQ(-50, constrain_float(c, -250, -50));
  143. EXPECT_EQ(-50, constrain_int16(c, -250, -50));
  144. EXPECT_EQ(-50, constrain_int32(c, -250, -50));
  145. EXPECT_EQ(-50, constrain_int64(c, -250, -50));
  146. } else {
  147. EXPECT_EQ(c, constrain_float(c, -250, -50));
  148. EXPECT_EQ(c, constrain_int16(c, -250, -50));
  149. EXPECT_EQ(c, constrain_int32(c, -250, -50));
  150. EXPECT_EQ(c, constrain_int64(c, -250, -50));
  151. }
  152. }
  153. for (int i = 0; i <= 2000; i++) {
  154. int c = i - 1000;
  155. if (c < -250) {
  156. EXPECT_EQ(-250, constrain_float(c, -250, 50));
  157. EXPECT_EQ(-250, constrain_int16(c, -250, 50));
  158. EXPECT_EQ(-250, constrain_int32(c, -250, 50));
  159. EXPECT_EQ(-250, constrain_int64(c, -250, 50));
  160. } else if(c > 50) {
  161. EXPECT_EQ(50, constrain_float(c, -250, 50));
  162. EXPECT_EQ(50, constrain_int16(c, -250, 50));
  163. EXPECT_EQ(50, constrain_int32(c, -250, 50));
  164. EXPECT_EQ(50, constrain_int64(c, -250, 50));
  165. } else {
  166. EXPECT_EQ(c, constrain_float(c, -250, 50));
  167. EXPECT_EQ(c, constrain_int16(c, -250, 50));
  168. EXPECT_EQ(c, constrain_int32(c, -250, 50));
  169. EXPECT_EQ(c, constrain_int64(c, -250, 50));
  170. }
  171. }
  172. EXPECT_EQ(20.0, constrain_value(20.0, 19.9, 20.1));
  173. EXPECT_EQ(20.0, constrain_value(20.0f, 19.9f, 20.1f));
  174. EXPECT_EQ(19.9, constrain_value(19.9, 19.9, 20.1));
  175. EXPECT_EQ(19.9f, constrain_value(19.9f, 19.9f, 20.1f));
  176. EXPECT_EQ(19.9, constrain_value(19.8, 19.9, 20.1));
  177. EXPECT_EQ(19.9f, constrain_value(19.8f, 19.9f, 20.1f));
  178. }
  179. TEST(MathWrapTest, Angle180)
  180. {
  181. // Full circle test
  182. for (int32_t i = 0; i < 36000; i += 100) {
  183. if (i < 18000) {
  184. // smaller pole position
  185. EXPECT_EQ(i, wrap_180_cd(i));
  186. EXPECT_EQ(-i, wrap_180_cd(-i));
  187. } else if (i == 18000) {
  188. // hit pole position -180/+180 degree
  189. EXPECT_EQ(i, wrap_180_cd(i));
  190. EXPECT_EQ(i, wrap_180_cd(-i));
  191. } else {
  192. // bigger pole position
  193. EXPECT_EQ(-(36000 - i), wrap_180_cd(i));
  194. EXPECT_EQ(36000 - i, wrap_180_cd(-i));
  195. }
  196. }
  197. EXPECT_EQ(4500.f, wrap_180_cd(4500.f));
  198. EXPECT_EQ(9000.f, wrap_180_cd(9000.f));
  199. EXPECT_EQ(18000.f, wrap_180_cd(18000.f));
  200. EXPECT_EQ(-17990.f, wrap_180_cd(18010.f));
  201. EXPECT_EQ(-9000.f, wrap_180_cd(27000.f));
  202. EXPECT_EQ(0.f, wrap_180_cd(36000.f));
  203. EXPECT_EQ(0.f, wrap_180_cd(72000.f));
  204. EXPECT_EQ(0.f, wrap_180_cd(360000.f));
  205. EXPECT_EQ(0.f, wrap_180_cd(720000.f));
  206. EXPECT_EQ(0.f, wrap_180_cd(-3600000000.f));
  207. EXPECT_EQ(-4500.f, wrap_180_cd(-4500.f));
  208. EXPECT_EQ(-9000.f, wrap_180_cd(-9000.f));
  209. EXPECT_EQ(18000.f, wrap_180_cd(-18000.f));
  210. EXPECT_EQ(17990.f, wrap_180_cd(-18010.f));
  211. EXPECT_EQ(9000.f, wrap_180_cd(-27000.f));
  212. EXPECT_EQ(0.f, wrap_180_cd(-36000.f));
  213. EXPECT_EQ(0.f, wrap_180_cd(-72000.f));
  214. }
  215. TEST(MathWrapTest, Angle360)
  216. {
  217. // Full circle test
  218. for (int32_t i = 0; i <= 36000; i += 100) {
  219. if (i == 0) {
  220. // hit pole position
  221. EXPECT_EQ(i, wrap_360_cd(i));
  222. EXPECT_EQ(i, wrap_360_cd(-i));
  223. } else if (i < 36000) {
  224. // between pole position
  225. EXPECT_EQ(i, wrap_360_cd(i));
  226. EXPECT_EQ(36000 - i, wrap_360_cd(-i));
  227. } else if (i == 36000) {
  228. // hit pole position
  229. EXPECT_EQ(0, wrap_360_cd(i));
  230. EXPECT_EQ(0, wrap_360_cd(-i));
  231. }
  232. }
  233. EXPECT_EQ(4500.f, wrap_360_cd(4500.f));
  234. EXPECT_EQ(9000.f, wrap_360_cd(9000.f));
  235. EXPECT_EQ(18000.f, wrap_360_cd(18000.f));
  236. EXPECT_EQ(27000.f, wrap_360_cd(27000.f));
  237. EXPECT_EQ(0.f, wrap_360_cd(36000.f));
  238. EXPECT_EQ(5.f, wrap_360_cd(36005.f));
  239. EXPECT_EQ(0.f, wrap_360_cd(72000.f));
  240. EXPECT_EQ(0.f, wrap_360_cd(360000.f));
  241. EXPECT_EQ(0.f, wrap_360_cd(720000.f));
  242. EXPECT_EQ( 0.f, wrap_360_cd(-3600000000.f));
  243. EXPECT_EQ(31500.f, wrap_360_cd(-4500.f));
  244. EXPECT_EQ(27000.f, wrap_360_cd(-9000.f));
  245. EXPECT_EQ(18000.f, wrap_360_cd(-18000.f));
  246. EXPECT_EQ(9000.f, wrap_360_cd(-27000.f));
  247. EXPECT_EQ(0.f, wrap_360_cd(-36000.f));
  248. EXPECT_EQ(35995.0f,wrap_360_cd(-36005.f));
  249. EXPECT_EQ(0.f, wrap_360_cd(-72000.f));
  250. }
  251. TEST(MathWrapTest, AnglePI)
  252. {
  253. const float accuracy = 1.0e-5;
  254. EXPECT_NEAR(M_PI, wrap_PI(M_PI), accuracy);
  255. EXPECT_NEAR(0.f, wrap_PI(M_2PI), accuracy);
  256. EXPECT_NEAR(0, wrap_PI(M_PI * 10), accuracy);
  257. }
  258. TEST(MathWrapTest, Angle2PI)
  259. {
  260. const float accuracy = 1.0e-5;
  261. EXPECT_NEAR(M_PI, wrap_2PI(M_PI), accuracy);
  262. EXPECT_NEAR(0.f, wrap_2PI(M_2PI), accuracy);
  263. EXPECT_NEAR(0.f, wrap_2PI(M_PI * 10), accuracy);
  264. EXPECT_NEAR(0.f, wrap_2PI(0.f), accuracy);
  265. EXPECT_NEAR(M_PI, wrap_2PI(-M_PI), accuracy);
  266. EXPECT_NEAR(0, wrap_2PI(-M_2PI), accuracy);
  267. }
  268. AP_GTEST_MAIN()
  269. #pragma GCC diagnostic pop