test_perpendicular.cpp 2.8 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374
  1. #include <AP_gtest.h>
  2. #include <AP_Math/vector2.h>
  3. #include <AP_Math/vector3.h>
  4. #define EXPECT_VECTOR2F_EQ(v1, v2) \
  5. do { \
  6. EXPECT_FLOAT_EQ(v1[0], v2[0]); \
  7. EXPECT_FLOAT_EQ(v1[1], v2[1]); \
  8. } while (false);
  9. #define EXPECT_VECTOR3F_EQ(v1, v2) \
  10. do { \
  11. EXPECT_FLOAT_EQ(v1[0], v2[0]); \
  12. EXPECT_FLOAT_EQ(v1[1], v2[1]); \
  13. EXPECT_FLOAT_EQ(v1[2], v2[2]); \
  14. } while (false);
  15. #define PERP_TEST_2D(px,py, vx,vy, ex,ey) \
  16. do { \
  17. Vector2f p(px,py); \
  18. Vector2f v(vx,vy); \
  19. Vector2f expected(ex,ey); \
  20. Vector2f result; \
  21. result = Vector2f::perpendicular(p, v); \
  22. EXPECT_VECTOR2F_EQ(expected, result); \
  23. } while (false)
  24. #define PERP_TEST_3D(px,py,pz, vx,vy,vz, ex,ey,ez) \
  25. do { \
  26. Vector3f p(px,py,pz); \
  27. Vector3f v(vx,vy,vz); \
  28. Vector3f expected(ex,ey,ez); \
  29. Vector3f result; \
  30. result = Vector3f::perpendicular(p, v); \
  31. EXPECT_VECTOR3F_EQ(expected, result); \
  32. } while (false)
  33. void foo() { }
  34. TEST(ThreatTests, Distance)
  35. {
  36. PERP_TEST_2D( 0.0f,0.0f, 0.0f,0.0f, 0.0f,0.0f);
  37. PERP_TEST_2D( 0.0f,0.0f, 1.0f,0.0f, 0.0f,-1.0f);
  38. PERP_TEST_2D( 2.0f,0.0f, 1.0f,0.0f, 0.0f,-1.0f);
  39. PERP_TEST_2D( 0.0f,2.0f, 1.0f,0.0f, 0.0f,1.0f);
  40. PERP_TEST_2D( 0.0f,2.0f, 1.0f,2.0f, -2.0f,1.0f);
  41. PERP_TEST_2D( 2.0f,0.0f, 1.0f,2.0f, 2.0f,-1.0f);
  42. // 2D cases for the 3D code:
  43. PERP_TEST_3D( 0.0f,0.0f,0.0f, 0.0f,0.0f,0.0f, 0.0f,0.0f,0.0f);
  44. PERP_TEST_3D( 0.0f,0.0f,0.0f, 1.0f,0.0f,0.0f, 0.0f,0.0f,0.0f);
  45. PERP_TEST_3D( 2.0f,0.0f,0.0f, 1.0f,0.0f,0.0f, 0.0f,0.0f,0.0f);
  46. foo();
  47. PERP_TEST_3D( 0.0f,2.0f,0.0f, 1.0f,0.0f,0.0f, 0.0f,2.0f,0.0f);
  48. PERP_TEST_3D( 0.0f,2.0f,0.0f, 1.0f,2.0f,0.0f, -0.8f,0.4f,0.0f);
  49. PERP_TEST_3D( 2.0f,0.0f,0.0f, 1.0f,2.0f,0.0f, 1.6f,-0.8f,0.0f);
  50. // 3D-specific tests
  51. PERP_TEST_3D( 1.0f,1.0f,1.0f, 1.0f,0.0f,0.0f, 0.0f,1.0f,1.0f);
  52. PERP_TEST_3D( -1.0f,-1.0f,-1.0f, -1.0f,0.0f,0.0f, 0.0f,-1.0f,-1.0f);
  53. PERP_TEST_3D(1.0f,1.0f,0.0f, 1.0f,0.0f,0.0f, 0.0f,1.0f,0.0f);
  54. PERP_TEST_3D(1.0f,1.0f,1.0f, 1.0f,-1.0f,0.0f, 1.0f,1.0f,1.0f);
  55. PERP_TEST_3D(1.0f,1.0f,1.0f, 1.0f,-1.0f,1.0f, 0.66666666f,1.33333333f,0.66666666f);
  56. }
  57. AP_GTEST_MAIN()
  58. int hal = 0; // bizarrely, this fixes an undefined-symbol error but doesn't raise a type exception. Yay.