From e0fa053c790955f874ac5b812702e9124609e67a Mon Sep 17 00:00:00 2001 From: Adam M Rivera Date: Sat, 17 Mar 2012 01:47:29 -0500 Subject: [PATCH] AP_Declination: The exception signs unpacking logic was incorrect. I was shifting a 1 value left y%8 which would have needed a the signs to be packed right to left. My packed signs byte was packed left to right (left most being the 0 position) so I needed to reverse the shifting. --- libraries/AP_Declination/AP_Declination.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index 96a1828515..adcc81e0be 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -165,7 +165,7 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y) uint8_t sign = (uint8_t)pgm_read_byte_far(&exception_signs[x][y/8]); // Check the sign bit for this index - if(sign & (1 << y%8)) + if(sign & (0x80 >> y%8)) val = -val; return val;