APM:Libraries
polygon.cpp
Go to the documentation of this file.
1 //
2 // Unit tests for the AP_Math polygon code
3 //
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_Math/AP_Math.h>
7 
8 void setup();
9 void loop();
10 
12 
13 /*
14  * this is the boundary of the 2010 outback challenge
15  * Note that the last point must be the same as the first for the
16  * Polygon_outside() algorithm
17  */
18 static const Vector2l OBC_boundary[] = {
19  Vector2l(-265695640, 1518373730),
20  Vector2l(-265699560, 1518394050),
21  Vector2l(-265768230, 1518411420),
22  Vector2l(-265773080, 1518403440),
23  Vector2l(-265815110, 1518419500),
24  Vector2l(-265784860, 1518474690),
25  Vector2l(-265994890, 1518528860),
26  Vector2l(-266092110, 1518747420),
27  Vector2l(-266454780, 1518820530),
28  Vector2l(-266435720, 1518303500),
29  Vector2l(-265875990, 1518344050),
30  Vector2l(-265695640, 1518373730)
31 };
32 
33 static const struct {
35  bool outside;
36 } test_points[] = {
37  { Vector2l(-266398870, 1518220000), true },
38  { Vector2l(-266418700, 1518709260), false },
39  { Vector2l(-350000000, 1490000000), true },
40  { Vector2l(0, 0), true },
41  { Vector2l(-265768150, 1518408250), false },
42  { Vector2l(-265774060, 1518405860), true },
43  { Vector2l(-266435630, 1518303440), true },
44  { Vector2l(-266435650, 1518313540), false },
45  { Vector2l(-266435690, 1518303530), false },
46  { Vector2l(-266435690, 1518303490), true },
47  { Vector2l(-265875990, 1518344049), true },
48  { Vector2l(-265875990, 1518344051), false },
49  { Vector2l(-266454781, 1518820530), true },
50  { Vector2l(-266454779, 1518820530), true },
51  { Vector2l(-266092109, 1518747420), true },
52  { Vector2l(-266092111, 1518747420), false },
53  { Vector2l(-266092110, 1518747421), true },
54  { Vector2l(-266092110, 1518747419), false },
55  { Vector2l(-266092111, 1518747421), true },
56  { Vector2l(-266092109, 1518747421), true },
57  { Vector2l(-266092111, 1518747419), false },
58 };
59 
60 /*
61  * polygon tests
62  */
63 void setup(void)
64 {
65  uint32_t count;
66  bool all_passed = true;
67  uint32_t start_time;
68 
69  hal.console->printf("polygon unit tests\n\n");
70 
71  if (!Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary))) {
72  hal.console->printf("OBC boundary is not complete!\n");
73  all_passed = false;
74  }
75 
76  if (Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary)-1)) {
77  hal.console->printf("Polygon_complete test failed\n");
78  all_passed = false;
79  }
80 
81  for (uint32_t i = 0; i < ARRAY_SIZE(test_points); i++) {
83  OBC_boundary, ARRAY_SIZE(OBC_boundary));
84  hal.console->printf("%10f,%10f %s %s\n",
85  (double)(1.0e-7f * test_points[i].point.x),
86  (double)(1.0e-7f * test_points[i].point.y),
87  result ? "OUTSIDE" : "INSIDE ",
88  result == test_points[i].outside ? "PASS" : "FAIL");
89  if (result != test_points[i].outside) {
90  all_passed = false;
91  }
92  }
93  hal.console->printf("%s\n", all_passed ? "TEST PASSED" : "TEST FAILED");
94 
95  hal.console->printf("Speed test:\n");
96  start_time = AP_HAL::micros();
97  for (count = 0; count < 1000; count++) {
98  for (uint32_t i = 0; i < ARRAY_SIZE(test_points); i++) {
100  OBC_boundary, ARRAY_SIZE(OBC_boundary));
101  if (result != test_points[i].outside) {
102  all_passed = false;
103  }
104  }
105  }
106  hal.console->printf("%u usec/call\n", (unsigned)((AP_HAL::micros()
107  - start_time)/(count * ARRAY_SIZE(test_points))));
108  hal.console->printf("%s\n", all_passed ? "ALL TESTS PASSED" : "TEST FAILED");
109 }
110 
111 void loop(void){}
112 
113 AP_HAL_MAIN();
struct timespec start_time
Definition: system.cpp:16
bool Polygon_complete(const Vector2< T > *V, unsigned n)
Definition: polygon.cpp:86
AP_HAL::UARTDriver * console
Definition: HAL.h:110
const char * result
Definition: Printf.cpp:16
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define f(i)
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const HAL & get_HAL()
bool outside
Definition: polygon.cpp:35
static const Vector2l OBC_boundary[]
Definition: polygon.cpp:18
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: polygon.cpp:11
Vector2< int32_t > Vector2l
Definition: vector2.h:237
void loop()
Definition: polygon.cpp:111
bool Polygon_outside(const Vector2< T > &P, const Vector2< T > *V, unsigned n)
Definition: polygon.cpp:38
void setup()
Definition: polygon.cpp:63
static const struct @132 test_points[]
uint32_t micros()
Definition: system.cpp:152
Vector2l point
Definition: polygon.cpp:34
AP_HAL_MAIN()