SmartRTL_test.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135
  1. #include "SmartRTL_test.h"
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Baro/AP_Baro.h>
  4. #include <AP_Compass/AP_Compass.h>
  5. #include <AP_GPS/AP_GPS.h>
  6. #include <AP_InertialSensor/AP_InertialSensor.h>
  7. #include <AP_NavEKF2/AP_NavEKF2.h>
  8. #include <AP_NavEKF3/AP_NavEKF3.h>
  9. #include <AP_RangeFinder/AP_RangeFinder.h>
  10. #include <AP_SerialManager/AP_SerialManager.h>
  11. const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  12. // INS and Baro declaration
  13. static AP_InertialSensor ins;
  14. static Compass compass;
  15. static AP_GPS gps;
  16. static AP_Baro barometer;
  17. static AP_SerialManager serial_manager;
  18. class DummyVehicle {
  19. public:
  20. RangeFinder rangefinder;
  21. NavEKF2 EKF2{&ahrs, rangefinder};
  22. NavEKF3 EKF3{&ahrs, rangefinder};
  23. AP_AHRS_NavEKF ahrs{EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
  24. };
  25. static DummyVehicle vehicle;
  26. AP_AHRS_NavEKF &ahrs(vehicle.ahrs);
  27. AP_SmartRTL smart_rtl{true};
  28. AP_BoardConfig board_config;
  29. void setup();
  30. void loop();
  31. void reset();
  32. void check_path(const std::vector<Vector3f> &correct_path, const char* test_name, uint32_t time_us);
  33. void setup()
  34. {
  35. hal.console->printf("SmartRTL test\n");
  36. board_config.init();
  37. smart_rtl.init();
  38. }
  39. void loop()
  40. {
  41. if (!hal.console->is_initialized()) {
  42. return;
  43. }
  44. uint32_t reference_time, run_time;
  45. hal.console->printf("--------------------\n");
  46. // reset path and upload "test_path_before" to smart_rtl
  47. reference_time = AP_HAL::micros();
  48. reset();
  49. run_time = AP_HAL::micros() - reference_time;
  50. // check path after initial load (no simplification or pruning)
  51. check_path(test_path_after_adding, "append", run_time);
  52. // test simplifications
  53. reference_time = AP_HAL::micros();
  54. while (!smart_rtl.request_thorough_cleanup(AP_SmartRTL::THOROUGH_CLEAN_SIMPLIFY_ONLY)) {
  55. smart_rtl.run_background_cleanup();
  56. }
  57. run_time = AP_HAL::micros() - reference_time;
  58. check_path(test_path_after_simplifying, "simplify", run_time);
  59. // test both simplification and pruning
  60. hal.scheduler->delay(5); // delay 5 milliseconds because request_through_cleanup uses millisecond timestamps
  61. reset();
  62. reference_time = AP_HAL::micros();
  63. while (!smart_rtl.request_thorough_cleanup(AP_SmartRTL::THOROUGH_CLEAN_ALL)) {
  64. smart_rtl.run_background_cleanup();
  65. }
  66. run_time = AP_HAL::micros() - reference_time;
  67. check_path(test_path_complete, "simplify and pruning", run_time);
  68. // delay before next display
  69. hal.scheduler->delay(5e3); // 5 seconds
  70. }
  71. // reset path (i.e. clear path and add home) and upload "test_path_before" to smart_rtl
  72. void reset()
  73. {
  74. smart_rtl.set_home(true, Vector3f{0.0f, 0.0f, 0.0f});
  75. for (Vector3f v : test_path_before) {
  76. smart_rtl.update(true, v);
  77. }
  78. }
  79. // compare the vector array passed in with the path held in the smart_rtl object
  80. void check_path(const std::vector<Vector3f>& correct_path, const char* test_name, uint32_t time_us)
  81. {
  82. // check number of points
  83. bool num_points_match = correct_path.size() == smart_rtl.get_num_points();
  84. uint16_t points_to_compare = MIN(correct_path.size(), smart_rtl.get_num_points());
  85. // check all points match
  86. bool points_match = true;
  87. uint16_t failure_index = 0;
  88. for (uint16_t i = 0; i < points_to_compare; i++) {
  89. if (smart_rtl.get_point(i) != correct_path[i]) {
  90. failure_index = i;
  91. points_match = false;
  92. }
  93. }
  94. // display overall results
  95. hal.console->printf("%s: %s time:%u us\n", test_name, (num_points_match && points_match) ? "success" : "fail", (unsigned)time_us);
  96. // display number of points
  97. hal.console->printf(" expected %u points, got %u\n", (unsigned)correct_path.size(), (unsigned)smart_rtl.get_num_points());
  98. // display the first failed point and all subsequent points
  99. if (!points_match) {
  100. for (uint16_t j = failure_index; j < points_to_compare; j++) {
  101. const Vector3f& smartrtl_point = smart_rtl.get_point(j);
  102. hal.console->printf(" expected point %d to be %4.2f,%4.2f,%4.2f, got %4.2f,%4.2f,%4.2f\n",
  103. (int)j,
  104. (double)correct_path[j].x,
  105. (double)correct_path[j].y,
  106. (double)correct_path[j].z,
  107. (double)smartrtl_point.x,
  108. (double)smartrtl_point.y,
  109. (double)smartrtl_point.z
  110. );
  111. }
  112. }
  113. }
  114. AP_HAL_MAIN();