mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Declination: translated to AP_HAL
This commit is contained in:
parent
5d40074e4e
commit
9aada26e34
@ -14,13 +14,13 @@
|
||||
* of the License, or (at your option) any later version.
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <math.h>
|
||||
|
||||
|
||||
// 1 byte - 4 bits for value + 1 bit for sign + 3 bits for repeats => 8 bits
|
||||
struct row_value {
|
||||
|
||||
|
@ -1,34 +1,15 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// AVR runtime
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <I2C.h>
|
||||
#include <SPI.h>
|
||||
#include <Filter.h>
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
// all of this is needed to build with SITL
|
||||
#include <DataFlash.h>
|
||||
#include <AP_Semaphore.h>
|
||||
#include <APM_RC.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <AP_PeriodicProcess.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_GPS.h>
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
AP_Compass_HIL compass;
|
||||
#endif
|
||||
|
||||
FastSerialPort(Serial, 0);
|
||||
#include <AP_HAL_AVR.h>
|
||||
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();
|
||||
|
Loading…
Reference in New Issue
Block a user