mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Declination: fixed build of test sketch
This commit is contained in:
parent
deed802d1a
commit
c08fd50542
@ -1,19 +1,21 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
// AVR runtime
|
// AVR runtime
|
||||||
#include <avr/io.h>
|
|
||||||
#include <avr/eeprom.h>
|
|
||||||
#include <avr/pgmspace.h>
|
|
||||||
#include <math.h>
|
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
#include <AP_Declination.h>
|
#include <AP_Declination.h>
|
||||||
|
|
||||||
FastSerialPort(Serial, 0);
|
FastSerialPort(Serial, 0);
|
||||||
|
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
float declination = AP_Declination::get_declination(43.064191, -87.997498);
|
float declination;
|
||||||
Serial.printf("declination: %d", declination);
|
|
||||||
|
Serial.begin(115200);
|
||||||
|
|
||||||
|
declination = AP_Declination::get_declination(43.064191, -87.997498);
|
||||||
|
Serial.printf("declination: %f\n", declination);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void)
|
void loop(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user