From 9aada26e34f538310121f3db4bdc10bd0735b4b9 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Thu, 11 Oct 2012 13:34:23 -0700 Subject: [PATCH] AP_Declination: translated to AP_HAL --- libraries/AP_Declination/AP_Declination.cpp | 4 +- .../AP_Declination_test.pde | 45 ++++++------------- .../examples/AP_Declination_test/Arduino.h | 0 .../AP_Declination_test/nocore.inoflag | 0 4 files changed, 15 insertions(+), 34 deletions(-) create mode 100644 libraries/AP_Declination/examples/AP_Declination_test/Arduino.h create mode 100644 libraries/AP_Declination/examples/AP_Declination_test/nocore.inoflag diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index afe90db5fb..46ef5d6fd0 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -14,13 +14,13 @@ * of the License, or (at your option) any later version. */ -#include #include +#include +#include #include #include #include - // 1 byte - 4 bits for value + 1 bit for sign + 3 bits for repeats => 8 bits struct row_value { diff --git a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde index 25b9794d03..1eb3954dd5 100644 --- a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde +++ b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde @@ -1,34 +1,15 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -// AVR runtime -#include #include #include +#include #include #include -#include #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 -Arduino_Mega_ISR_Registry isr_registry; -AP_Baro_BMP085_HIL barometer; -AP_Compass_HIL compass; -#endif +#include -FastSerialPort(Serial, 0); +#include +const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; static const int16_t dec_tbl[37][73] = \ { \ @@ -103,16 +84,15 @@ void setup(void) uint16_t pass = 0, fail = 0; uint32_t total_time=0; - Serial.begin(115200); - Serial.print("Beginning Test. Please wait...\n"); + hal.console->print("Beginning Test. Please wait...\n"); for(int16_t i = -90; i <= 90; i+=5) { for(int16_t j = -180; j <= 180; j+=5) { - uint32_t t1 = micros(); + uint32_t t1 = hal.scheduler->micros(); declination = AP_Declination::get_declination(i, j); - total_time += micros() - t1; + total_time += hal.scheduler->micros() - t1; declination_test = get_declination(i, j); if(declination == declination_test) { @@ -121,15 +101,15 @@ void setup(void) } else { - Serial.printf("FAIL: %i, %i : %f, %f\n", i, j, declination, declination_test); + hal.console->printf("FAIL: %i, %i : %f, %f\n", i, j, declination, declination_test); fail++; } } } - Serial.print("Ending Test.\n\n"); - Serial.printf("Total Pass: %i\n", pass); - Serial.printf("Total Fail: %i\n", fail); - Serial.printf("Average time per call: %.1f usec\n", + hal.console->print("Ending Test.\n\n"); + hal.console->printf("Total Pass: %i\n", pass); + hal.console->printf("Total Fail: %i\n", fail); + hal.console->printf("Average time per call: %.1f usec\n", total_time/(float)(pass+fail)); } @@ -137,3 +117,4 @@ void loop(void) { } +AP_HAL_MAIN(); diff --git a/libraries/AP_Declination/examples/AP_Declination_test/Arduino.h b/libraries/AP_Declination/examples/AP_Declination_test/Arduino.h new file mode 100644 index 0000000000..e69de29bb2 diff --git a/libraries/AP_Declination/examples/AP_Declination_test/nocore.inoflag b/libraries/AP_Declination/examples/AP_Declination_test/nocore.inoflag new file mode 100644 index 0000000000..e69de29bb2