From 9888a4730fae278aa977b0ba6d8adf87cac607fd Mon Sep 17 00:00:00 2001
From: Adam M Rivera <a432511@gmail.com>
Date: Sun, 11 Mar 2012 12:22:37 -0500
Subject: [PATCH] AP_Declination: Changed PROGMEM read function to
 pgm_read_word_far to support the int16_t datatype.

---
 libraries/AP_Declination/AP_Declination.cpp | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp
index 67091feb9..b5d2cb370 100644
--- a/libraries/AP_Declination/AP_Declination.cpp
+++ b/libraries/AP_Declination/AP_Declination.cpp
@@ -76,10 +76,10 @@ AP_Declination::get_declination(float lat, float lon)
 	latmin_index= (90+latmin)/5;
 	lonmin_index= (180+lonmin)/5;
 
-	decSW = (int16_t)pgm_read_byte_far(&dec_tbl[latmin_index][lonmin_index]);
-	decSE = (int16_t)pgm_read_byte_far(&dec_tbl[latmin_index][lonmin_index+1]);
-	decNE = (int16_t)pgm_read_byte_far(&dec_tbl[latmin_index+1][lonmin_index+1]);
-	decNW = (int16_t)pgm_read_byte_far(&dec_tbl[latmin_index+1][lonmin_index]);
+	decSW = (int16_t)pgm_read_word_far(&dec_tbl[latmin_index][lonmin_index]);
+	decSE = (int16_t)pgm_read_word_far(&dec_tbl[latmin_index][lonmin_index+1]);
+	decNE = (int16_t)pgm_read_word_far(&dec_tbl[latmin_index+1][lonmin_index+1]);
+	decNW = (int16_t)pgm_read_word_far(&dec_tbl[latmin_index+1][lonmin_index]);
 
 	/* approximate declination within the grid using bilinear interpolation */
 	decmin = (lon - lonmin) / 5 * (decSE - decSW) + decSW;
-- 
GitLab