APM:Libraries
SmartRTL_test.cpp
Go to the documentation of this file.
1 #include "SmartRTL_test.h"
2 #include <AP_AHRS/AP_AHRS.h>
3 #include <AP_Baro/AP_Baro.h>
5 #include <AP_GPS/AP_GPS.h>
11 
13 
14 // INS and Baro declaration
17 static AP_GPS gps;
20 
21 class DummyVehicle {
22 public:
25  NavEKF3 EKF3{&ahrs, rangefinder};
27 };
28 
30 
31 AP_AHRS_NavEKF &ahrs(vehicle.ahrs);
34 
35 void setup();
36 void loop();
37 void reset();
38 void check_path(const std::vector<Vector3f> &correct_path, const char* test_name, uint32_t time_us);
39 
40 void setup()
41 {
42  hal.console->printf("SmartRTL test\n");
43  board_config.init();
44  smart_rtl.init();
45 }
46 
47 void loop()
48 {
49  if (!hal.console->is_initialized()) {
50  return;
51  }
52  uint32_t reference_time, run_time;
53 
54  hal.console->printf("--------------------\n");
55 
56  // reset path and upload "test_path_before" to smart_rtl
57  reference_time = AP_HAL::micros();
58  reset();
59  run_time = AP_HAL::micros() - reference_time;
60 
61  // check path after initial load (no simplification or pruning)
62  check_path(test_path_after_adding, "append", run_time);
63 
64  // test simplifications
65  reference_time = AP_HAL::micros();
68  }
69  run_time = AP_HAL::micros() - reference_time;
70  check_path(test_path_after_simplifying, "simplify", run_time);
71 
72  // test both simplification and pruning
73  hal.scheduler->delay(5); // delay 5 milliseconds because request_through_cleanup uses millisecond timestamps
74  reset();
75  reference_time = AP_HAL::micros();
78  }
79  run_time = AP_HAL::micros() - reference_time;
80  check_path(test_path_complete, "simplify and pruning", run_time);
81 
82  // delay before next display
83  hal.scheduler->delay(5e3); // 5 seconds
84 }
85 
86 // reset path (i.e. clear path and add home) and upload "test_path_before" to smart_rtl
87 void reset()
88 {
89  smart_rtl.set_home(true, Vector3f{0.0f, 0.0f, 0.0f});
90  for (Vector3f v : test_path_before) {
91  smart_rtl.update(true, v);
92  }
93 }
94 
95 // compare the vector array passed in with the path held in the smart_rtl object
96 void check_path(const std::vector<Vector3f>& correct_path, const char* test_name, uint32_t time_us)
97 {
98  // check number of points
99  bool num_points_match = correct_path.size() == smart_rtl.get_num_points();
100  uint16_t points_to_compare = MIN(correct_path.size(), smart_rtl.get_num_points());
101 
102  // check all points match
103  bool points_match = true;
104  uint16_t failure_index = 0;
105  for (uint16_t i = 0; i < points_to_compare; i++) {
106  if (smart_rtl.get_point(i) != correct_path[i]) {
107  failure_index = i;
108  points_match = false;
109  }
110  }
111 
112  // display overall results
113  hal.console->printf("%s: %s time:%u us\n", test_name, (num_points_match && points_match) ? "success" : "fail", (unsigned)time_us);
114 
115  // display number of points
116  hal.console->printf(" expected %u points, got %u\n", (unsigned)correct_path.size(), (unsigned)smart_rtl.get_num_points());
117 
118  // display the first failed point and all subsequent points
119  if (!points_match) {
120  for (uint16_t j = failure_index; j < points_to_compare; j++) {
121  const Vector3f& smartrtl_point = smart_rtl.get_point(j);
122  hal.console->printf(" expected point %d to be %4.2f,%4.2f,%4.2f, got %4.2f,%4.2f,%4.2f\n",
123  (int)j,
124  (double)correct_path[j].x,
125  (double)correct_path[j].y,
126  (double)correct_path[j].z,
127  (double)smartrtl_point.x,
128  (double)smartrtl_point.y,
129  (double)smartrtl_point.z
130  );
131  }
132  }
133 }
134 
135 AP_HAL_MAIN();
NavEKF2 EKF2
Definition: AHRS_Test.cpp:29
static DummyVehicle vehicle
Definition: AP_GPS.h:48
static AP_Baro barometer
AP_SerialManager serial_manager
std::vector< Vector3f > test_path_complete
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual bool is_initialized()=0
bool request_thorough_cleanup(ThoroughCleanupType clean_type=THOROUGH_CLEAN_DEFAULT)
void reset()
static AP_SerialManager serial_manager
AP_AHRS_NavEKF ahrs
Definition: AHRS_Test.cpp:31
const Vector3f & get_point(uint16_t index) const
Definition: AP_SmartRTL.h:45
std::vector< Vector3f > test_path_after_adding
#define MIN(a, b)
Definition: usb_conf.h:215
virtual void delay(uint16_t ms)=0
void run_background_cleanup()
AP_SmartRTL smart_rtl
#define x(i)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void check_path(const std::vector< Vector3f > &correct_path, const char *test_name, uint32_t time_us)
std::vector< Vector3f > test_path_before
Definition: SmartRTL_test.h:17
void update(bool position_ok, bool save_position)
T y
Definition: vector3.h:67
uint16_t get_num_points() const
static AP_InertialSensor ins
T z
Definition: vector3.h:67
AP_BoardConfig board_config
AP_HAL_MAIN()
RangeFinder rangefinder
float v
Definition: Printf.cpp:15
void setup()
const HAL & get_HAL()
void loop()
static AP_GPS gps
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void set_home(bool position_ok)
Catch-all header that defines all supported RangeFinder classes.
NavEKF3 EKF3
Definition: AHRS_Test.cpp:30
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static Compass compass
T x
Definition: vector3.h:67
std::vector< Vector3f > test_path_after_simplifying