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