AP_Declination: fixed example build

This commit is contained in:
Andrew Tridgell 2013-05-02 12:33:15 +10:00
parent 54b826a583
commit 261eb6d841
1 changed files with 2 additions and 2 deletions

View File

@ -61,8 +61,8 @@ static float get_declination(float lat, float lon)
uint8_t latmin_index, lonmin_index;
// Validate input values
lat = constrain(lat, -90, 90);
lon = constrain(lon, -180, 180);
lat = constrain_float(lat, -90, 90);
lon = constrain_float(lon, -180, 180);
latmin = floor(lat/5)*5;
lonmin = floor(lon/5)*5;