mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_Declination: Moved check for y index of zero to after the y index is properly transformed.
This commit is contained in:
parent
e99d26cfa3
commit
64c236800c
@ -171,17 +171,16 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y)
|
|||||||
return val;
|
return val;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// If we are looking for the first value we can just use the
|
|
||||||
// row_start value from declination_keys
|
|
||||||
if(y == 0) return declination_keys.row_start[x];
|
|
||||||
|
|
||||||
// Because the values were removed from the start of the
|
// Because the values were removed from the start of the
|
||||||
// original array (0-6) to the exception array, all the indicies
|
// original array (0-6) to the exception array, all the indicies
|
||||||
// in this main lookup need to be shifted left 7
|
// in this main lookup need to be shifted left 7
|
||||||
// EX: User enters 7 -> 7 is the first row in this array so it needs to be zero
|
// EX: User enters 7 -> 7 is the first row in this array so it needs to be zero
|
||||||
if(x >= 7) x -= 7;
|
if(x >= 7) x -= 7;
|
||||||
|
|
||||||
|
// If we are looking for the first value we can just use the
|
||||||
|
// row_start value from declination_keys
|
||||||
|
if(y == 0) return declination_keys.row_start[x];
|
||||||
|
|
||||||
// Init vars
|
// Init vars
|
||||||
row_value stval;
|
row_value stval;
|
||||||
int16_t offset = 0;
|
int16_t offset = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user