/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Math polygon code // #include #include #include #ifdef DESKTOP_BUILD // all of this is needed to build with SITL #include #include #include #include #include #include #include #include #include #include #include #include #include #include Arduino_Mega_ISR_Registry isr_registry; AP_Baro_BMP085_HIL barometer; AP_Compass_HIL compass; SITL sitl; #endif FastSerialPort(Serial, 0); static const struct { Vector2f wp1, wp2, location; bool passed; } test_points[] = { { Vector2f(-35.3647759314918, 149.16265692810987), Vector2f(-35.36279922658029, 149.16352169591426), Vector2f(-35.36214956969903, 149.16461410046492), true }, { Vector2f(-35.36438601157189, 149.16613916088568), Vector2f(-35.364432558610254, 149.16287313113048), Vector2f(-35.36491510034746, 149.16365837225004), false }, { Vector2f(0, 0), Vector2f(0, 1), Vector2f(0, 2), true }, { Vector2f(0, 0), Vector2f(0, 2), Vector2f(0, 1), false }, { Vector2f(0, 0), Vector2f(1, 0), Vector2f(2, 0), true }, { Vector2f(0, 0), Vector2f(2, 0), Vector2f(1, 0), false }, { Vector2f(0, 0), Vector2f(-1, 1), Vector2f(-2, 2), true }, }; #define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0])) static struct Location location_from_point(Vector2f pt) { struct Location loc = {0}; loc.lat = pt.x * 1.0e7; loc.lng = pt.y * 1.0e7; return loc; } static void test_passed_waypoint(void) { Serial.println("waypoint tests starting"); for (uint8_t i=0; i 180) { brg_error -= 360; } else if (brg_error < -180) { brg_error += 360; } if (fabs(dist - dist2) > 1.0 || brg_error > 1.0) { Serial.printf("Failed offset test brg_error=%f dist_error=%f\n", brg_error, dist-dist2); } } static const struct { float ofs_north, ofs_east, distance, bearing; } test_offsets[] = { { 1000, 1000, sqrt(2.0)*1000, 45 }, { 1000, -1000, sqrt(2.0)*1000, -45 }, { 1000, 0, 1000, 0 }, { 0, 1000, 1000, 90 }, }; static void test_offset(void) { struct Location loc; loc.lat = -35*1.0e7; loc.lng = 149*1.0e7; for (uint8_t i=0; i