mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Added AP_Declination library. It contains the lookup table (lat/lng -> declination) as well as a method that performs the lookup.
Signed-off-by: Andrew Tridgell <tridge@samba.org>
This commit is contained in:
parent
d10c4b76ad
commit
d2a07b1603
48
libraries/AP_Declination/AP_Declination.cpp
Normal file
48
libraries/AP_Declination/AP_Declination.cpp
Normal file
File diff suppressed because one or more lines are too long
25
libraries/AP_Declination/AP_Declination.h
Normal file
25
libraries/AP_Declination/AP_Declination.h
Normal file
@ -0,0 +1,25 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#ifndef AP_Declination_h
|
||||
#define AP_Declination_h
|
||||
|
||||
// Just incase it wasn't included elsewhere
|
||||
#include <avr/pgmspace.h>
|
||||
#include <math.h>
|
||||
|
||||
/*
|
||||
* Adam M Rivera
|
||||
* With direction from: Andrew Tridgell, Jason Short, Justin Beech
|
||||
*
|
||||
* Adapted from: http://www.societyofrobots.com/robotforum/index.php?topic=11855.0
|
||||
* Scott Ferguson
|
||||
* scottfromscott@gmail.com
|
||||
*
|
||||
*/
|
||||
class AP_Declination
|
||||
{
|
||||
public:
|
||||
static float get_declination(float lat, float lon);
|
||||
};
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user