APM:Libraries
location.cpp
Go to the documentation of this file.
1 //
2 // Unit tests for the AP_Math polygon code
3 //
4 
5 #define ALLOW_DOUBLE_MATH_FUNCTIONS
6 
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Math/AP_Math.h>
9 
10 void setup();
11 void loop();
12 
14 
15 static const struct {
17  bool passed;
18 } test_points[] = {
19  { Vector2f(-35.3647759314918f, 149.16265692810987f),
20  Vector2f(-35.36279922658029f, 149.16352169591426f),
21  Vector2f(-35.36214956969903f, 149.16461410046492f), true },
22  { Vector2f(-35.36438601157189f, 149.16613916088568f),
23  Vector2f(-35.364432558610254f, 149.16287313113048f),
24  Vector2f(-35.36491510034746f, 149.16365837225004f), false },
25  { Vector2f(0.0f, 0.0f),
26  Vector2f(0.0f, 1.0f),
27  Vector2f(0.0f, 2.0f), true },
28  { Vector2f(0.0f, 0.0f),
29  Vector2f(0.0f, 2.0f),
30  Vector2f(0.0f, 1.0f), false },
31  { Vector2f(0.0f, 0.0f),
32  Vector2f(1.0f, 0.0f),
33  Vector2f(2.0f, 0.0f), true },
34  { Vector2f(0.0f, 0.0f),
35  Vector2f(2.0f, 0.0f),
36  Vector2f(1.0f, 0.0f), false },
37  { Vector2f(0.0f, 0.0f),
38  Vector2f(-1.0f, 1.0f),
39  Vector2f(-2.0f, 2.0f), true },
40 };
41 
43 {
44  struct Location loc = {};
45  loc.lat = pt.x * 1.0e7f;
46  loc.lng = pt.y * 1.0e7f;
47  return loc;
48 }
49 
50 static void test_passed_waypoint(void)
51 {
52  hal.console->printf("waypoint tests starting\n");
53  for (uint8_t i = 0; i < ARRAY_SIZE(test_points); i++) {
55  struct Location wp1 = location_from_point(test_points[i].wp1);
56  struct Location wp2 = location_from_point(test_points[i].wp2);
57  if (location_passed_point(loc, wp1, wp2) != test_points[i].passed) {
58  hal.console->printf("Failed waypoint test %u\n", (unsigned)i);
59  return;
60  }
61  }
62  hal.console->printf("waypoint tests OK\n");
63 }
64 
65 static void test_one_offset(const struct Location &loc,
66  float ofs_north, float ofs_east,
67  float dist, float bearing)
68 {
69  struct Location loc2;
70  float dist2, bearing2;
71 
72  loc2 = loc;
73  uint32_t t1 = AP_HAL::micros();
74  location_offset(loc2, ofs_north, ofs_east);
75  hal.console->printf("location_offset took %u usec\n",
76  (unsigned)(AP_HAL::micros() - t1));
77  dist2 = get_distance(loc, loc2);
78  bearing2 = get_bearing_cd(loc, loc2) * 0.01f;
79  float brg_error = bearing2-bearing;
80  if (brg_error > 180) {
81  brg_error -= 360;
82  } else if (brg_error < -180) {
83  brg_error += 360;
84  }
85 
86  if (fabsf(dist - dist2) > 1.0f ||
87  brg_error > 1.0f) {
88  hal.console->printf("Failed offset test brg_error=%f dist_error=%f\n",
89  (double)brg_error, (double)(dist - dist2));
90  }
91 }
92 
93 static const struct {
95 } test_offsets[] = {
96  { 1000.0f, 1000.0f, sqrtf(2.0f) * 1000.0f, 45.0f },
97  { 1000.0f, -1000.0f, sqrtf(2.0f) * 1000.0f, -45.0f },
98  { 1000.0f, 0.0f, 1000.0f, 0.0f },
99  { 0.0f, 1000.0f, 1000.0f, 90.0f },
100 };
101 
102 static void test_offset(void)
103 {
104  struct Location loc {};
105 
106  loc.lat = -35 * 1.0e7f;
107  loc.lng = 149 * 1.0e7f;
108 
109  for (uint8_t i = 0; i < ARRAY_SIZE(test_offsets); i++) {
110  test_one_offset(loc,
114  test_offsets[i].bearing);
115  }
116 }
117 
118 
119 /*
120  test position accuracy for floating point versus integer positions
121  */
122 static void test_accuracy(void)
123 {
124  struct Location loc {};
125 
126  loc.lat = 0.0e7f;
127  loc.lng = -120.0e7f;
128 
129  struct Location loc2 = loc;
130  Vector2f v((loc.lat * 1.0e-7f), (loc.lng* 1.0e-7f));
131  Vector2f v2;
132 
133  loc2 = loc;
134  loc2.lat += 10000000;
135  v2 = Vector2f(loc2.lat * 1.0e-7f, loc2.lng * 1.0e-7f);
136  hal.console->printf("1 degree lat dist=%.4f\n", (double)get_distance(loc, loc2));
137 
138  loc2 = loc;
139  loc2.lng += 10000000;
140  v2 = Vector2f(loc2.lat * 1.0e-7f, loc2.lng * 1.0e-7f);
141  hal.console->printf("1 degree lng dist=%.4f\n", (double)get_distance(loc, loc2));
142 
143  for (int32_t i = 0; i < 100; i++) {
144  loc2 = loc;
145  loc2.lat += i;
146  v2 = Vector2f((loc.lat + i) * 1.0e-7f, loc.lng * 1.0e-7f);
147  if (v2 != v) {
148  hal.console->printf("lat v2 != v at i=%d dist=%.4f\n", (int)i, (double)get_distance(loc, loc2));
149  break;
150  }
151  }
152  for (int32_t i = 0; i < 100; i++) {
153  loc2 = loc;
154  loc2.lng += i;
155  v2 = Vector2f(loc.lat * 1.0e-7f, (loc.lng + i) * 1.0e-7f);
156  if (v2 != v) {
157  hal.console->printf("lng v2 != v at i=%d dist=%.4f\n", (int)i, (double)get_distance(loc, loc2));
158  break;
159  }
160  }
161 
162  for (int32_t i = 0; i < 100; i++) {
163  loc2 = loc;
164  loc2.lat -= i;
165  v2 = Vector2f((loc.lat - i) * 1.0e-7f, loc.lng * 1.0e-7f);
166  if (v2 != v) {
167  hal.console->printf("-lat v2 != v at i=%d dist=%.4f\n", (int)i, (double)get_distance(loc, loc2));
168  break;
169  }
170  }
171  for (int32_t i = 0; i < 100; i++) {
172  loc2 = loc;
173  loc2.lng -= i;
174  v2 = Vector2f(loc.lat * 1.0e-7f, (loc.lng - i) * 1.0e-7f);
175  if (v2 != v) {
176  hal.console->printf("-lng v2 != v at i=%d dist=%.4f\n", (int)i, (double)get_distance(loc, loc2));
177  break;
178  }
179  }
180 }
181 
182 static const struct {
183  int32_t v, wv;
184 } wrap_180_tests[] = {
185  { 32000, -4000 },
186  { 1500 + 100*36000, 1500 },
187  { -1500 - 100*36000, -1500 },
188 };
189 
190 static const struct {
191  int32_t v, wv;
192 } wrap_360_tests[] = {
193  { 32000, 32000 },
194  { 1500 + 100*36000, 1500 },
195  { -1500 - 100*36000, 34500 },
196 };
197 
198 static const struct {
199  float v, wv;
200 } wrap_PI_tests[] = {
201  { 0.2f*M_PI, 0.2f*M_PI },
202  { 0.2f*M_PI + 100*M_PI, 0.2f*M_PI },
203  { -0.2f*M_PI - 100*M_PI, -0.2f*M_PI },
204 };
205 
206 static void test_wrap_cd(void)
207 {
208  for (uint8_t i = 0; i < ARRAY_SIZE(wrap_180_tests); i++) {
209  int32_t r = wrap_180_cd(wrap_180_tests[i].v);
210  if (r != wrap_180_tests[i].wv) {
211  hal.console->printf("wrap_180: v=%ld wv=%ld r=%ld\n",
212  (long)wrap_180_tests[i].v,
213  (long)wrap_180_tests[i].wv,
214  (long)r);
215  }
216  }
217 
218  for (uint8_t i = 0; i < ARRAY_SIZE(wrap_360_tests); i++) {
219  int32_t r = wrap_360_cd(wrap_360_tests[i].v);
220  if (r != wrap_360_tests[i].wv) {
221  hal.console->printf("wrap_360: v=%ld wv=%ld r=%ld\n",
222  (long)wrap_360_tests[i].v,
223  (long)wrap_360_tests[i].wv,
224  (long)r);
225  }
226  }
227 
228  for (uint8_t i = 0; i < ARRAY_SIZE(wrap_PI_tests); i++) {
229  float r = wrap_PI(wrap_PI_tests[i].v);
230  if (fabsf(r - wrap_PI_tests[i].wv) > 0.001f) {
231  hal.console->printf("wrap_PI: v=%f wv=%f r=%f\n",
232  (double)wrap_PI_tests[i].v,
233  (double)wrap_PI_tests[i].wv,
234  (double)r);
235  }
236  }
237 
238  hal.console->printf("wrap_cd tests done\n");
239 }
240 
242 {
243 
244  #define D2R DEG_TO_RAD_DOUBLE
245 
246  /* Maximum allowable error in quantities with units of length (in meters). */
247  static const double MAX_DIST_ERROR_M = 1e-6;
248  /* Maximum allowable error in quantities with units of angle (in sec of arc).
249  * 1 second of arc on the equator is ~31 meters. */
250  static const double MAX_ANGLE_ERROR_SEC = 1e-7;
251  static const double MAX_ANGLE_ERROR_RAD = (MAX_ANGLE_ERROR_SEC * (D2R / (double)3600.0));
252 
253  /* Semi-major axis. */
254  static const double EARTH_A = 6378137.0;
255  /* Semi-minor axis. */
256  static const double EARTH_B = 6356752.31424517929553985595703125;
257 
258 
259  #define NUM_COORDS 10
260  Vector3d llhs[NUM_COORDS];
261  llhs[0] = Vector3d(0, 0, 0); /* On the Equator and Prime Meridian. */
262  llhs[1] = Vector3d(0, 180*D2R, 0); /* On the Equator. */
263  llhs[2] = Vector3d(0, 90*D2R, 0); /* On the Equator. */
264  llhs[3] = Vector3d(0, -90*D2R, 0); /* On the Equator. */
265  llhs[4] = Vector3d(90*D2R, 0, 0); /* North pole. */
266  llhs[5] = Vector3d(-90*D2R, 0, 0); /* South pole. */
267  llhs[6] = Vector3d(90*D2R, 0, 22); /* 22m above the north pole. */
268  llhs[7] = Vector3d(-90*D2R, 0, 22); /* 22m above the south pole. */
269  llhs[8] = Vector3d(0, 0, 22); /* 22m above the Equator and Prime Meridian. */
270  llhs[9] = Vector3d(0, 180*D2R, 22); /* 22m above the Equator. */
271 
272  Vector3d ecefs[NUM_COORDS];
273  ecefs[0] = Vector3d(EARTH_A, 0, 0);
274  ecefs[1] = Vector3d(-EARTH_A, 0, 0);
275  ecefs[2] = Vector3d(0, EARTH_A, 0);
276  ecefs[3] = Vector3d(0, -EARTH_A, 0);
277  ecefs[4] = Vector3d(0, 0, EARTH_B);
278  ecefs[5] = Vector3d(0, 0, -EARTH_B);
279  ecefs[6] = Vector3d(0, 0, (EARTH_B+22));
280  ecefs[7] = Vector3d(0, 0, -(EARTH_B+22));
281  ecefs[8] = Vector3d((22+EARTH_A), 0, 0);
282  ecefs[9] = Vector3d(-(22+EARTH_A), 0, 0);
283 
284  hal.console->printf("TESTING wgsllh2ecef\n");
285  for (int i = 0; i < NUM_COORDS; i++) {
286 
287  Vector3d ecef;
288  wgsllh2ecef(llhs[i], ecef);
289 
290  double x_err = fabs(ecef[0] - ecefs[i][0]);
291  double y_err = fabs(ecef[1] - ecefs[i][1]);
292  double z_err = fabs(ecef[2] - ecefs[i][2]);
293  if ((x_err < MAX_DIST_ERROR_M) &&
294  (y_err < MAX_DIST_ERROR_M) &&
295  (z_err < MAX_DIST_ERROR_M)) {
296  hal.console->printf("passing llh to ecef test %d\n", i);
297  } else {
298  hal.console->printf("failed llh to ecef test %d: ", i);
299  hal.console->printf("(%f - %f) (%f - %f) (%f - %f) => %.10f %.10f %.10f\n",
300  ecef[0], ecefs[i][0], ecef[1], ecefs[i][1], ecef[2], ecefs[i][2], x_err, y_err, z_err);
301  }
302 
303  }
304 
305  hal.console->printf("TESTING wgsecef2llh\n");
306  for (int i = 0; i < NUM_COORDS; i++) {
307 
308  Vector3d llh;
309  wgsecef2llh(ecefs[i], llh);
310 
311  double lat_err = fabs(llh[0] - llhs[i][0]);
312  double lon_err = fabs(llh[1] - llhs[i][1]);
313  double hgt_err = fabs(llh[2] - llhs[i][2]);
314  if ((lat_err < MAX_ANGLE_ERROR_RAD) &&
315  (lon_err < MAX_ANGLE_ERROR_RAD) &&
316  (hgt_err < MAX_DIST_ERROR_M)) {
317  hal.console->printf("passing exef to llh test %d\n", i);
318  } else {
319  hal.console->printf("failed ecef to llh test %d: ", i);
320  hal.console->printf("%.10f %.10f %.10f\n", lat_err, lon_err, hgt_err);
321 
322  }
323 
324  }
325 }
326 
327 /*
328  * polygon tests
329  */
330 void setup(void)
331 {
333  test_offset();
334  test_accuracy();
335  test_wrap_cd();
337  hal.console->printf("ALL TESTS DONE\n");
338 }
339 
340 void loop(void){}
341 
342 AP_HAL_MAIN();
void setup()
Definition: location.cpp:330
Vector2< float > Vector2f
Definition: vector2.h:239
#define NUM_COORDS
#define D2R
static const struct @130 wrap_360_tests[]
static const struct @127 test_points[]
Vector3< double > Vector3d
Definition: vector3.h:247
float ofs_north
Definition: location.cpp:94
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void wgsllh2ecef(const Vector3d &llh, Vector3d &ecef)
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
Definition: AP_Math.cpp:140
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
float ofs_east
Definition: location.cpp:94
void wgsecef2llh(const Vector3d &ecef, Vector3d &llh)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: location.cpp:13
static void test_wrap_cd(void)
Definition: location.cpp:206
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
float distance
Definition: location.cpp:94
int32_t v
Definition: location.cpp:183
static struct Location location_from_point(Vector2f pt)
Definition: location.cpp:42
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
static const struct @131 wrap_PI_tests[]
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
static void test_wgs_conversion_functions(void)
Definition: location.cpp:241
static void test_offset(void)
Definition: location.cpp:102
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
#define f(i)
float bearing
Definition: location.cpp:94
static void test_accuracy(void)
Definition: location.cpp:122
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const HAL & get_HAL()
static const struct @128 test_offsets[]
Vector2f location
Definition: location.cpp:16
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
static void test_passed_waypoint(void)
Definition: location.cpp:50
bool passed
Definition: location.cpp:17
int32_t wv
Definition: location.cpp:183
void loop()
Definition: location.cpp:340
AP_HAL_MAIN()
Vector2f wp2
Definition: location.cpp:16
#define M_PI
Definition: definitions.h:10
bool location_passed_point(const struct Location &location, const struct Location &point1, const struct Location &point2)
Definition: location.cpp:80
static const struct @129 wrap_180_tests[]
uint32_t micros()
Definition: system.cpp:152
static void test_one_offset(const struct Location &loc, float ofs_north, float ofs_east, float dist, float bearing)
Definition: location.cpp:65
Vector2f wp1
Definition: location.cpp:16