mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
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.
This commit is contained in:
parent
d9c9e0e608
commit
e99d26cfa3
@ -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]);
|
uint8_t sign = (uint8_t)pgm_read_byte_far(&exception_signs[x][y/8]);
|
||||||
|
|
||||||
// Check the sign bit for this index
|
// Check the sign bit for this index
|
||||||
if(sign & (1 << y%8))
|
if(sign & (0x80 >> y%8))
|
||||||
val = -val;
|
val = -val;
|
||||||
|
|
||||||
return val;
|
return val;
|
||||||
|
Loading…
Reference in New Issue
Block a user