mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Declination: Moved rows with large spikes in delta to their own unsigned exception rows. The signs are in a separate packed array.
This commit is contained in:
parent
782c1aaaa3
commit
63ce400f77
@ -20,19 +20,18 @@
|
||||
#include <avr/pgmspace.h>
|
||||
#include <math.h>
|
||||
|
||||
// 2 bytes - 9 bits for value + 5 bits for repeats => 14 padded to 16
|
||||
|
||||
// 1 byte - 4 bits for value + 1 bit for sign + 3 bits for repeats => 8 bits
|
||||
struct row_value{
|
||||
|
||||
// Offset has a max value of 203 and a min value of -197
|
||||
// If we take the abs value of each offset and store its sign in a separate bit
|
||||
// we can save a lot of wasted 8 bits and simplify reading the offsets
|
||||
uint8_t abs_offset;
|
||||
// Offset has a max value of 15
|
||||
uint8_t abs_offset:4;
|
||||
|
||||
// Sign of the offset, 0 = negative, 1 = positive
|
||||
uint8_t offset_sign:1;
|
||||
|
||||
// The highest repeat is 29
|
||||
uint8_t repeats:5;
|
||||
// The highest repeat is 7
|
||||
uint8_t repeats:3;
|
||||
};
|
||||
|
||||
// 76 bytes - 8 bits per 37 row_start + 8 bits per 37 row_length
|
||||
@ -47,41 +46,64 @@ struct row_keys{
|
||||
uint8_t row_length[37];
|
||||
};
|
||||
|
||||
// 730 bytes
|
||||
static const uint8_t exceptions[10][73] PROGMEM = \
|
||||
{ \
|
||||
{150,145,140,135,130,125,120,115,110,105,100,95,90,85,80,75,70,65,60,55,50,45,40,35,30,25,20,15,10,5,0,4,9,14,19,24,29,34,39,44,49,54,59,64,69,74,79,84,89,94,99,104,109,114,119,124,129,134,139,144,149,154,159,164,169,174,179,175,170,165,160,155,150}, \
|
||||
{143,137,131,126,120,115,110,105,100,95,90,85,80,75,71,66,62,57,53,48,44,39,35,31,27,22,18,14,9,5,1,3,7,11,16,20,25,29,34,38,43,47,52,57,61,66,71,76,81,86,91,96,101,107,112,117,123,128,134,140,146,151,157,163,169,175,178,172,166,160,154,148,143}, \
|
||||
{130,124,118,112,107,101,96,92,87,82,78,74,70,65,61,57,54,50,46,42,38,34,31,27,23,19,16,12,8,4,1,2,6,10,14,18,22,26,30,34,38,43,47,51,56,61,65,70,75,79,84,89,94,100,105,111,116,122,128,135,141,148,155,162,170,177,174,166,159,151,144,137,130}, \
|
||||
{111,104,99,94,89,85,81,77,73,70,66,63,60,56,53,50,46,43,40,36,33,30,26,23,20,16,13,10,6,3,0,3,6,9,13,16,20,24,28,32,36,40,44,48,52,57,61,65,70,74,79,84,88,93,98,103,109,115,121,128,135,143,152,162,172,176,165,154,144,134,125,118,111}, \
|
||||
{85,81,77,74,71,68,65,63,60,58,56,53,51,49,46,43,41,38,35,32,29,26,23,19,16,13,10,7,4,1,1,3,6,9,13,16,19,23,26,30,34,38,42,46,50,54,58,62,66,70,74,78,83,87,91,95,100,105,110,117,124,133,144,159,178,160,141,125,112,103,96,90,85}, \
|
||||
{62,60,58,57,55,54,52,51,50,48,47,46,44,42,41,39,36,34,31,28,25,22,19,16,13,10,7,4,2,0,3,5,8,10,13,16,19,22,26,29,33,37,41,45,49,53,56,60,64,67,70,74,77,80,83,86,89,91,94,97,101,105,111,130,109,84,77,74,71,68,66,64,62}, \
|
||||
{46,46,45,44,44,43,42,42,41,41,40,39,38,37,36,35,33,31,28,26,23,20,16,13,10,7,4,1,1,3,5,7,9,12,14,16,19,22,26,29,33,36,40,44,48,51,55,58,61,64,66,68,71,72,74,74,75,74,72,68,61,48,25,2,22,33,40,43,45,46,47,46,46}, \
|
||||
{6,9,12,15,18,21,23,25,27,28,27,24,17,4,14,34,49,56,60,60,60,58,56,53,50,47,43,40,36,32,28,25,21,17,13,9,5,1,2,6,10,14,17,21,24,28,31,34,37,39,41,42,43,43,41,38,33,25,17,8,0,4,8,10,10,10,8,7,4,2,0,3,6}, \
|
||||
{22,24,26,28,30,32,33,31,23,18,81,96,99,98,95,93,89,86,82,78,74,70,66,62,57,53,49,44,40,36,32,27,23,19,14,10,6,1,2,6,10,15,19,23,27,31,35,38,42,45,49,52,55,57,60,61,63,63,62,61,57,53,47,40,33,28,23,21,19,19,19,20,22}, \
|
||||
{168,173,178,176,171,166,161,156,151,146,141,136,131,126,121,116,111,106,101,96,91,86,81,76,71,66,61,56,51,46,41,36,31,26,21,16,11,6,1,3,8,13,18,23,28,33,38,43,48,53,58,63,68,73,78,83,88,93,98,103,108,113,118,123,128,133,138,143,148,153,158,163,168} \
|
||||
};
|
||||
|
||||
// 100 bytes
|
||||
static const uint8_t exception_signs[10][10] PROGMEM = \
|
||||
{ \
|
||||
{192,0,0,0,0,0,15,255,240,0}, \
|
||||
{192,0,0,0,0,0,7,255,240,0}, \
|
||||
{192,0,0,0,0,0,3,255,224,0}, \
|
||||
{192,0,0,0,0,0,0,255,224,0}, \
|
||||
{192,0,0,0,0,0,0,127,192,0}, \
|
||||
{192,0,0,0,0,0,0,7,128,0}, \
|
||||
{228,160,0,0,0,0,0,191,255,0}, \
|
||||
{255,224,15,255,255,255,254,0,127,1}, \
|
||||
{255,3,255,255,255,255,255,224,3,1}, \
|
||||
{240,0,7,255,255,255,255,255,255,1} \
|
||||
};
|
||||
|
||||
// 76 bytes - Instance of the struct defined above
|
||||
// I decided NOT to store this in PROGMEM because it is small and the expense of pulling
|
||||
// the value out of the PROGMEM is too high
|
||||
static const row_keys declination_keys = \
|
||||
{ \
|
||||
{150,143,130,111,85,62,46,36,30,25,21,18,16,14,12,11,10,9,9,9,8,8,8,7,6,6,5,4,4,4,3,4,4,4,6,22,168}, \
|
||||
{7,39,39,39,36,39,46,39,37,33,34,36,35,37,35,38,33,40,41,41,28,38,37,41,50,48,37,35,33,43,49,48,47,54,44,46,7}, \
|
||||
{36,30,25,21,18,16,14,12,11,10,9,9,9,8,8,8,7,6,6,5,4,4,4,3,4,4,4}, \
|
||||
{39,37,33,35,37,35,37,36,39,34,41,42,41,28,38,38,41,50,48,37,35,33,43,49,48,47,54}, \
|
||||
};
|
||||
|
||||
// 1409 total values @ 2 bytes each = 2818 bytes
|
||||
// 1075 total values @ 1 bytes each = 1075 bytes
|
||||
static const row_value declination_values[] PROGMEM = \
|
||||
{ \
|
||||
{0,1,0},{5,0,29},{4,0,0},{5,0,18},{203,1,0},{5,1,14},{4,0,0}, \
|
||||
{0,1,0},{6,0,1},{5,0,0},{6,0,0},{5,0,8},{4,0,0},{5,0,0},{4,0,0},{5,0,0},{4,0,0},{5,0,0},{4,0,0},{5,0,0},{4,0,2},{5,0,0},{4,0,1},{5,0,0},{4,0,4},{5,0,0},{4,0,0},{5,0,0},{4,0,0},{5,0,0},{4,0,0},{5,0,0},{4,0,0},{5,0,1},{4,0,0},{5,0,6},{197,1,0},{6,1,0},{5,1,1},{6,1,0},{5,1,0},{6,1,2},{5,1,0},{6,1,3},{3,1,0},{6,0,4}, \
|
||||
{0,1,0},{6,0,2},{5,0,0},{6,0,0},{5,0,0},{4,0,0},{5,0,1},{4,0,2},{5,0,0},{4,0,1},{3,0,0},{4,0,4},{3,0,0},{4,0,2},{3,0,0},{4,0,2},{3,0,1},{4,0,8},{5,0,0},{4,0,1},{5,0,1},{4,0,0},{5,0,1},{4,0,0},{5,0,2},{194,1,0},{5,1,0},{6,1,0},{5,1,0},{6,1,1},{7,1,0},{6,1,0},{7,1,2},{8,1,0},{7,1,0},{3,0,0},{8,0,0},{7,0,0},{8,0,0}, \
|
||||
{0,1,0},{7,0,0},{5,0,2},{4,0,3},{3,0,0},{4,0,0},{3,0,1},{4,0,0},{3,0,1},{4,0,0},{3,0,1},{4,0,0},{3,0,1},{4,0,0},{3,0,1},{4,0,0},{3,0,1},{4,0,0},{3,0,4},{4,0,0},{3,0,0},{4,0,8},{5,0,0},{4,0,1},{5,0,0},{4,0,0},{5,0,1},{4,0,0},{5,0,1},{201,1,0},{6,1,2},{7,1,1},{8,1,0},{9,1,0},{10,1,1},{4,1,0},{11,0,1},{10,0,1},{9,0,0}, \
|
||||
{0,1,0},{4,0,1},{3,0,3},{2,0,0},{3,0,0},{2,0,1},{3,0,0},{2,0,1},{3,0,1},{2,0,0},{3,0,5},{4,0,0},{3,0,5},{2,0,1},{3,0,1},{4,0,0},{3,0,1},{4,0,0},{3,0,0},{4,0,12},{5,0,0},{4,0,2},{195,1,0},{5,1,1},{7,1,1},{9,1,0},{11,1,0},{15,1,0},{19,1,0},{18,0,0},{19,0,0},{16,0,0},{13,0,0},{9,0,0},{7,0,0},{6,0,0}, \
|
||||
{0,1,0},{2,0,1},{1,0,0},{2,0,0},{1,0,0},{2,0,0},{1,0,1},{2,0,0},{1,0,1},{2,0,1},{1,0,0},{2,0,0},{3,0,0},{2,0,0},{3,0,9},{2,0,1},{3,0,0},{2,0,0},{3,0,0},{2,0,0},{3,0,3},{4,0,0},{3,0,0},{4,0,5},{3,0,0},{4,0,1},{3,0,1},{4,0,0},{3,0,4},{2,0,0},{3,0,1},{198,1,0},{4,1,0},{6,1,0},{19,1,0},{21,0,0},{25,0,0},{7,0,0},{3,0,2}, \
|
||||
{0,1,1},{1,0,1},{0,1,0},{1,0,1},{0,1,0},{1,0,0},{0,1,0},{1,0,5},{2,0,1},{3,0,0},{2,0,0},{3,0,1},{4,0,0},{3,0,4},{2,0,4},{3,0,0},{2,0,1},{3,0,1},{4,0,0},{3,0,0},{4,0,0},{3,0,0},{4,0,2},{3,0,0},{4,0,0},{3,0,2},{2,0,1},{3,0,0},{1,0,0},{2,0,0},{0,1,0},{1,0,0},{1,1,0},{2,1,0},{4,1,0},{7,1,0},{13,1,0},{23,1,0},{27,1,0},{20,1,0},{11,1,0},{7,1,0},{3,1,0},{2,1,0},{1,1,1},{1,0,0}, \
|
||||
{0,1,4},{1,0,0},{0,1,2},{1,0,0},{0,1,2},{1,0,3},{2,0,1},{3,0,3},{4,0,1},{3,0,1},{2,0,1},{3,0,0},{2,0,0},{1,0,0},{2,0,1},{1,0,0},{2,0,0},{3,0,4},{4,0,1},{3,0,0},{4,0,0},{3,0,2},{2,0,2},{1,0,1},{0,1,0},{1,1,1},{3,1,0},{4,1,0},{6,1,0},{8,1,0},{11,1,0},{13,1,1},{10,1,0},{9,1,0},{7,1,0},{5,1,0},{4,1,0},{2,1,0},{1,1,2}, \
|
||||
{0,1,6},{1,0,0},{0,1,6},{1,0,2},{2,0,0},{3,0,2},{4,0,2},{3,0,3},{2,0,0},{1,0,0},{2,0,0},{1,0,2},{2,0,2},{3,0,3},{4,0,0},{3,0,3},{2,0,1},{1,0,1},{0,1,0},{1,1,1},{2,1,0},{4,1,0},{5,1,0},{6,1,0},{7,1,0},{8,1,0},{9,1,0},{8,1,0},{6,1,0},{7,1,0},{6,1,0},{4,1,1},{3,1,0},{2,1,0},{1,1,0},{2,1,0},{0,1,0}, \
|
||||
{0,1,1},{1,1,0},{0,1,1},{1,0,0},{0,1,6},{1,1,0},{1,0,0},{0,1,0},{1,0,1},{2,0,1},{3,0,0},{4,0,3},{3,0,0},{4,0,0},{3,0,1},{2,0,0},{1,0,7},{2,0,0},{3,0,6},{2,0,0},{1,0,2},{0,1,0},{1,1,0},{2,1,0},{3,1,1},{5,1,1},{6,1,0},{7,1,0},{6,1,2},{4,1,2},{3,1,1},{2,1,2},{1,1,1}, \
|
||||
{0,1,0},{1,1,0},{0,1,13},{1,0,1},{2,0,1},{3,0,0},{4,0,5},{3,0,1},{1,0,0},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{0,1,1},{1,0,0},{0,1,0},{2,0,2},{3,0,1},{2,0,0},{3,0,0},{2,0,1},{1,0,0},{0,1,1},{1,1,0},{2,1,1},{4,1,1},{5,1,4},{4,1,0},{3,1,1},{4,1,0},{2,1,0},{3,1,0},{2,1,2},{1,1,2}, \
|
||||
{0,1,0},{1,1,0},{0,1,13},{1,0,2},{2,0,0},{4,0,0},{3,0,0},{5,0,0},{3,0,0},{5,0,0},{4,0,1},{3,0,0},{2,0,1},{1,0,2},{0,1,2},{1,1,0},{0,1,1},{1,0,0},{2,0,2},{3,0,0},{2,0,1},{1,0,1},{0,1,0},{1,1,0},{2,1,1},{3,1,1},{4,1,0},{5,1,0},{4,1,0},{5,1,0},{4,1,0},{3,1,1},{1,1,0},{3,1,0},{2,1,4},{1,1,3}, \
|
||||
{0,1,0},{1,1,0},{0,1,7},{0,1,5},{1,0,1},{2,0,1},{3,0,0},{4,0,5},{3,0,1},{1,0,0},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{0,1,1},{1,0,0},{0,1,0},{2,0,2},{3,0,1},{2,0,0},{3,0,0},{2,0,1},{1,0,0},{0,1,1},{1,1,0},{2,1,1},{4,1,1},{5,1,4},{4,1,0},{3,1,1},{4,1,0},{2,1,0},{3,1,0},{2,1,2},{1,1,2}, \
|
||||
{0,1,0},{1,1,0},{0,1,7},{0,1,5},{1,0,2},{2,0,0},{4,0,0},{3,0,0},{5,0,0},{3,0,0},{5,0,0},{4,0,1},{3,0,0},{2,0,1},{1,0,2},{0,1,2},{1,1,0},{0,1,1},{1,0,0},{2,0,2},{3,0,0},{2,0,1},{1,0,1},{0,1,0},{1,1,0},{2,1,1},{3,1,1},{4,1,0},{5,1,0},{4,1,0},{5,1,0},{4,1,0},{3,1,1},{1,1,0},{3,1,0},{2,1,4},{1,1,3}, \
|
||||
{0,1,1},{1,1,0},{0,1,7},{1,0,0},{0,1,4},{1,0,0},{2,0,1},{3,0,0},{4,0,2},{5,0,0},{4,0,0},{3,0,1},{2,0,1},{1,0,1},{0,1,2},{1,1,1},{2,1,0},{1,1,0},{0,1,0},{1,0,1},{2,0,3},{1,0,1},{1,1,2},{2,1,0},{3,1,1},{4,1,2},{3,1,1},{2,1,0},{1,1,0},{2,1,1},{1,1,0},{2,1,1},{1,1,0},{2,1,0},{1,1,3}, \
|
||||
{0,1,2},{1,1,0},{0,1,5},{1,0,0},{0,1,4},{1,0,2},{2,0,0},{4,0,0},{3,0,0},{4,0,1},{5,0,0},{4,0,0},{3,0,1},{2,0,0},{1,0,1},{0,1,2},{1,1,0},{2,1,0},{1,1,0},{3,1,0},{2,1,0},{1,1,0},{0,1,1},{2,0,2},{1,0,0},{2,0,0},{0,1,1},{1,1,1},{2,1,1},{3,1,2},{4,1,0},{2,1,1},{1,1,2},{2,1,0},{1,1,1},{2,1,0},{1,1,5}, \
|
||||
{0,1,0},{1,1,0},{0,1,9},{1,0,0},{0,1,2},{1,0,2},{3,0,2},{4,0,3},{3,0,0},{2,0,1},{1,0,0},{0,1,2},{1,1,1},{2,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,0},{1,1,0},{0,1,0},{1,0,0},{2,0,0},{1,0,0},{2,0,1},{0,1,0},{1,0,0},{1,1,2},{2,1,1},{3,1,1},{2,1,1},{1,1,1},{0,1,0},{1,1,2},{2,1,0},{1,1,5}, \
|
||||
{0,1,4},{1,1,0},{0,1,3},{1,0,0},{0,1,3},{1,0,0},{0,1,0},{1,0,0},{2,0,1},{3,0,1},{4,0,3},{3,0,0},{2,0,0},{1,0,0},{0,1,2},{1,1,0},{2,1,3},{3,1,0},{2,1,0},{3,1,0},{1,1,1},{1,0,1},{2,0,0},{1,0,0},{2,0,0},{1,0,0},{0,1,2},{1,1,0},{2,1,0},{1,1,0},{2,1,0},{3,1,0},{2,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,0},{1,1,9}, \
|
||||
{0,1,13},{1,0,0},{0,1,1},{2,0,0},{1,0,0},{3,0,3},{4,0,1},{3,0,1},{1,0,1},{0,1,1},{1,1,0},{2,1,3},{3,1,0},{2,1,3},{0,1,2},{2,0,0},{1,0,0},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{1,1,0},{0,1,0},{1,1,0},{2,1,0},{1,1,0},{2,1,1},{0,1,0},{1,1,0},{0,1,1},{1,1,0},{0,1,0},{1,1,7}, \
|
||||
{0,1,6},{1,1,0},{0,1,0},{1,0,0},{0,1,4},{1,0,0},{0,1,0},{2,0,0},{1,0,0},{3,0,0},{2,0,0},{4,0,0},{3,0,0},{4,0,1},{2,0,2},{0,1,1},{1,1,0},{2,1,8},{1,1,1},{0,1,1},{1,0,1},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{0,1,0},{1,1,0},{0,1,0},{1,1,1},{2,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,2},{1,1,1},{0,1,0},{2,1,0},{1,1,2},{0,1,0},{1,1,0}, \
|
||||
{0,1,11},{1,0,0},{0,1,2},{1,0,0},{2,0,0},{1,0,0},{3,0,0},{2,0,0},{4,0,0},{3,0,0},{4,0,0},{3,0,0},{2,0,1},{1,0,0},{0,1,0},{1,1,1},{2,1,1},{3,1,0},{2,1,2},{1,1,0},{2,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,0},{1,0,0},{0,1,0},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{0,1,1},{1,1,0},{0,1,0},{1,1,2},{0,1,3},{1,1,0},{0,1,0},{1,1,6},{0,1,0},{1,1,0}, \
|
||||
{0,1,0},{1,1,0},{0,1,7},{0,1,1},{1,0,0},{0,1,2},{1,0,2},{3,0,2},{4,0,3},{3,0,0},{2,0,1},{1,0,0},{0,1,2},{1,1,1},{2,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,0},{1,1,0},{0,1,0},{1,0,0},{2,0,0},{1,0,0},{2,0,1},{0,1,0},{1,0,0},{1,1,2},{2,1,1},{3,1,1},{2,1,1},{1,1,1},{0,1,0},{1,1,2},{2,1,0},{1,1,5}, \
|
||||
{0,1,4},{1,1,0},{0,1,3},{1,0,0},{0,1,3},{1,0,0},{0,1,0},{1,0,0},{2,0,1},{3,0,1},{4,0,3},{3,0,0},{2,0,0},{1,0,0},{0,1,2},{1,1,0},{2,1,3},{3,1,0},{2,1,0},{3,1,0},{1,1,1},{1,0,1},{2,0,0},{1,0,0},{2,0,0},{1,0,0},{0,1,2},{1,1,0},{2,1,0},{1,1,0},{2,1,0},{3,1,0},{2,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,0},{1,1,7},{1,1,1}, \
|
||||
{0,1,7},{0,1,5},{1,0,0},{0,1,1},{2,0,0},{1,0,0},{3,0,3},{4,0,1},{3,0,1},{1,0,1},{0,1,1},{1,1,0},{2,1,3},{3,1,0},{2,1,3},{0,1,2},{2,0,0},{1,0,0},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{1,1,0},{0,1,0},{1,1,0},{2,1,0},{1,1,0},{2,1,1},{0,1,0},{1,1,0},{0,1,1},{1,1,0},{0,1,0},{1,1,7}, \
|
||||
{0,1,6},{1,1,0},{0,1,0},{1,0,0},{0,1,4},{1,0,0},{0,1,0},{2,0,0},{1,0,0},{3,0,0},{2,0,0},{4,0,0},{3,0,0},{4,0,1},{2,0,2},{0,1,1},{1,1,0},{2,1,7},{2,1,0},{1,1,1},{0,1,1},{1,0,1},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{0,1,0},{1,1,0},{0,1,0},{1,1,1},{2,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,2},{1,1,1},{0,1,0},{2,1,0},{1,1,2},{0,1,0},{1,1,0}, \
|
||||
{0,1,7},{0,1,3},{1,0,0},{0,1,2},{1,0,0},{2,0,0},{1,0,0},{3,0,0},{2,0,0},{4,0,0},{3,0,0},{4,0,0},{3,0,0},{2,0,1},{1,0,0},{0,1,0},{1,1,1},{2,1,1},{3,1,0},{2,1,2},{1,1,0},{2,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,0},{1,0,0},{0,1,0},{2,0,0},{1,0,0},{0,1,0},{1,0,0},{0,1,1},{1,1,0},{0,1,0},{1,1,2},{0,1,3},{1,1,0},{0,1,0},{1,1,6},{0,1,0},{1,1,0}, \
|
||||
{0,1,2},{1,0,0},{0,1,1},{1,1,0},{0,1,3},{1,0,0},{0,1,2},{1,0,2},{2,0,0},{3,0,0},{2,0,0},{3,0,0},{4,0,0},{3,0,1},{2,0,0},{1,0,1},{0,1,0},{1,1,0},{2,1,2},{3,1,0},{2,1,1},{1,1,0},{2,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,2},{1,0,0},{0,1,0},{1,0,1},{0,1,0},{1,0,0},{0,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,5},{1,1,7},{0,1,0}, \
|
||||
{0,1,5},{1,1,0},{0,1,4},{1,0,0},{0,1,1},{1,0,1},{2,0,2},{3,0,4},{2,0,0},{1,0,0},{0,1,0},{1,1,1},{2,1,6},{1,1,1},{0,1,0},{1,1,1},{0,1,2},{1,0,1},{0,1,0},{1,0,0},{0,1,1},{1,0,0},{0,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,7},{1,1,7}, \
|
||||
{0,1,3},{1,1,0},{0,1,7},{1,0,0},{0,1,0},{1,0,0},{2,0,3},{3,0,3},{2,0,0},{1,0,1},{0,1,0},{1,1,1},{2,1,2},{3,1,0},{1,1,0},{2,1,0},{1,1,0},{2,1,0},{0,1,1},{1,1,1},{0,1,2},{1,0,0},{0,1,0},{1,0,0},{0,1,1},{1,0,0},{0,1,3},{1,1,0},{0,1,2},{1,0,0},{0,1,3},{1,1,0},{0,1,0},{1,1,0},{2,1,0},{1,1,1},{2,1,0},{0,1,0}, \
|
||||
{0,1,1},{1,1,0},{0,1,2},{1,1,0},{0,1,5},{1,0,2},{2,0,1},{3,0,0},{2,0,0},{3,0,2},{2,0,1},{1,0,0},{0,1,1},{1,1,0},{2,1,0},{1,1,0},{2,1,4},{1,1,1},{0,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,0},{1,0,0},{0,1,0},{1,0,1},{0,1,8},{1,0,0},{0,1,0},{1,0,0},{0,1,3},{1,1,1},{0,1,0},{1,1,0},{2,1,0},{1,1,0},{2,1,0}, \
|
||||
{0,1,1},{1,1,0},{0,1,2},{1,1,0},{0,1,5},{1,0,2},{2,0,1},{3,0,0},{2,0,0},{3,0,2},{2,0,1},{1,0,0},{0,1,1},{1,1,0},{2,1,0},{1,1,0},{2,1,4},{1,1,1},{0,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,0},{1,0,0},{0,1,0},{1,0,1},{0,1,7},{0,1,0},{1,0,0},{0,1,0},{1,0,0},{0,1,3},{1,1,1},{0,1,0},{1,1,0},{2,1,0},{1,1,0},{2,1,0}, \
|
||||
{0,1,0},{1,1,1},{0,1,1},{1,1,0},{0,1,0},{1,1,0},{0,1,3},{1,0,0},{0,1,0},{1,0,0},{2,0,2},{3,0,0},{2,0,0},{4,0,0},{3,0,0},{2,0,2},{1,0,0},{0,1,0},{1,1,2},{2,1,4},{1,1,0},{2,1,0},{0,1,0},{1,1,0},{0,1,0},{1,1,1},{0,1,2},{1,0,0},{0,1,0},{1,0,0},{0,1,0},{1,0,0},{0,1,5},{1,0,0},{0,1,0},{1,0,1},{0,1,0},{1,0,0},{0,1,1},{1,1,4},{2,1,1}, \
|
||||
{0,1,0},{2,1,0},{1,1,0},{0,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,3},{1,0,0},{0,1,0},{2,0,2},{3,0,0},{2,0,0},{3,0,0},{4,0,0},{3,0,0},{2,0,1},{1,0,1},{1,1,0},{0,1,0},{2,1,0},{1,1,0},{2,1,1},{1,1,0},{2,1,2},{1,1,0},{0,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,0},{1,1,0},{1,0,0},{0,1,1},{1,0,0},{0,1,0},{1,0,0},{0,1,1},{1,0,0},{0,1,2},{1,0,3},{0,1,0},{1,0,0},{0,1,2},{1,1,0},{2,1,0},{1,1,1},{2,1,0},{1,1,0},{2,1,0}, \
|
||||
{0,1,0},{1,1,1},{2,1,0},{1,1,1},{0,1,0},{1,1,0},{0,1,0},{1,1,0},{0,1,0},{1,0,0},{0,1,0},{2,0,0},{1,0,0},{2,0,0},{3,0,1},{2,0,0},{4,0,1},{3,0,0},{2,0,1},{1,0,0},{0,1,1},{1,1,0},{2,1,0},{1,1,0},{2,1,2},{1,1,0},{2,1,1},{1,1,0},{0,1,0},{1,1,2},{0,1,0},{1,1,0},{0,1,3},{1,0,0},{0,1,1},{1,0,0},{0,1,0},{1,0,0},{0,1,0},{1,0,0},{0,1,0},{1,0,2},{2,0,0},{1,0,1},{0,1,1},{1,1,3},{2,1,0},{1,1,0}, \
|
||||
@ -92,10 +114,7 @@ static const row_value declination_values[] PROGMEM = \
|
||||
{0,1,0},{3,1,1},{2,1,0},{3,1,0},{2,1,0},{1,1,0},{2,1,0},{1,1,1},{0,1,1},{2,0,1},{3,0,0},{4,0,0},{6,0,0},{5,0,0},{7,0,0},{6,0,0},{5,0,0},{3,0,1},{1,0,0},{0,1,1},{1,1,0},{2,1,3},{3,1,0},{2,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,1},{1,1,0},{2,1,5},{1,1,2},{0,1,2},{1,0,0},{2,0,0},{3,0,2},{4,0,0},{3,0,0},{4,0,0},{3,0,0},{2,0,1},{1,0,0},{1,1,0},{0,1,0},{2,1,0},{1,1,0},{2,1,0},{3,1,0},{2,1,0},{3,1,0}, \
|
||||
{0,1,0},{2,1,0},{3,1,1},{2,1,0},{3,1,0},{2,1,1},{1,1,1},{0,1,1},{2,0,1},{4,0,0},{6,0,0},{7,0,1},{8,0,0},{7,0,0},{5,0,0},{3,0,0},{2,0,0},{1,0,0},{0,1,0},{1,1,1},{2,1,1},{3,1,0},{2,1,0},{3,1,2},{2,1,0},{3,1,2},{1,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,4},{1,1,1},{0,1,1},{1,0,0},{2,0,0},{3,0,0},{4,0,0},{5,0,0},{4,0,1},{5,0,0},{4,0,0},{2,0,1},{1,0,0},{0,1,0},{1,1,0},{2,1,3},{3,1,1},{2,1,0}, \
|
||||
{0,1,0},{3,1,2},{2,1,0},{3,1,0},{2,1,2},{1,1,0},{0,1,1},{2,0,0},{3,0,0},{5,0,0},{8,0,0},{9,0,0},{10,0,1},{7,0,0},{5,0,0},{3,0,0},{1,0,0},{0,1,0},{1,1,1},{2,1,0},{3,1,0},{2,1,0},{3,1,3},{4,1,0},{3,1,7},{2,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,0},{1,1,0},{2,1,0},{0,1,2},{2,0,0},{3,0,0},{4,0,0},{5,0,0},{7,0,0},{5,0,0},{6,0,0},{4,0,1},{2,0,0},{0,1,1},{1,1,1},{2,1,1},{3,1,2},{2,1,0}, \
|
||||
{0,1,0},{3,1,5},{2,1,1},{1,1,0},{0,1,0},{1,0,0},{2,0,0},{5,0,0},{8,0,0},{12,0,0},{14,0,0},{13,0,0},{9,0,0},{6,0,0},{3,0,0},{1,0,0},{0,1,0},{2,1,0},{1,1,0},{3,1,0},{2,1,0},{3,1,0},{4,1,0},{3,1,1},{4,1,0},{3,1,0},{4,1,1},{3,1,0},{4,1,0},{3,1,2},{4,1,0},{3,1,1},{4,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,2},{0,1,1},{1,0,0},{2,0,0},{4,0,0},{5,0,0},{7,0,0},{8,0,0},{6,0,1},{5,0,0},{3,0,0},{1,0,1},{1,1,1},{2,1,0},{3,1,0},{2,1,0},{3,1,1},{2,1,0}, \
|
||||
{0,1,0},{3,1,4},{2,1,2},{1,1,0},{1,0,0},{3,0,0},{7,0,0},{13,0,0},{18,0,0},{20,0,0},{15,0,0},{7,0,0},{4,0,0},{0,1,1},{2,1,1},{3,1,2},{4,1,0},{3,1,0},{4,1,2},{3,1,0},{4,1,5},{3,1,0},{4,1,2},{3,1,0},{4,1,0},{3,1,0},{4,1,0},{3,1,2},{2,1,1},{1,1,1},{0,1,0},{2,0,0},{3,0,0},{5,0,0},{8,0,1},{9,0,0},{8,0,0},{4,0,1},{2,0,0},{0,1,1},{2,1,0},{1,1,0},{3,1,0},{2,1,1}, \
|
||||
{0,1,0},{2,1,4},{1,1,0},{2,0,0},{8,0,0},{41,0,0},{63,0,0},{15,0,0},{3,0,0},{1,1,0},{3,1,0},{2,1,0},{4,1,0},{3,1,0},{4,1,5},{5,1,0},{4,1,1},{5,1,0},{4,1,2},{5,1,0},{4,1,1},{5,1,0},{4,1,1},{5,1,0},{3,1,0},{4,1,1},{5,1,0},{4,1,4},{3,1,0},{4,1,0},{3,1,0},{4,1,0},{3,1,1},{2,1,0},{3,1,0},{1,1,0},{2,1,0},{0,1,0},{1,0,1},{4,0,1},{6,0,0},{7,0,1},{5,0,1},{2,0,1},{0,1,1},{1,1,0}, \
|
||||
{0,1,0},{5,1,1},{2,0,0},{5,0,14},{197,0,0},{5,1,18},{4,1,0}, \
|
||||
{0,1,0},{3,1,5},{2,1,1},{1,1,0},{0,1,0},{1,0,0},{2,0,0},{5,0,0},{8,0,0},{12,0,0},{14,0,0},{13,0,0},{9,0,0},{6,0,0},{3,0,0},{1,0,0},{0,1,0},{2,1,0},{1,1,0},{3,1,0},{2,1,0},{3,1,0},{4,1,0},{3,1,1},{4,1,0},{3,1,0},{4,1,1},{3,1,0},{4,1,0},{3,1,2},{4,1,0},{3,1,1},{4,1,0},{3,1,0},{2,1,0},{3,1,0},{2,1,2},{0,1,1},{1,0,0},{2,0,0},{4,0,0},{5,0,0},{7,0,0},{8,0,0},{6,0,1},{5,0,0},{3,0,0},{1,0,1},{1,1,1},{2,1,0},{3,1,0},{2,1,0},{3,1,1},{2,1,0} \
|
||||
};
|
||||
|
||||
float
|
||||
@ -129,15 +148,52 @@ AP_Declination::get_declination(float lat, float lon)
|
||||
int16_t
|
||||
AP_Declination::get_lookup_value(uint8_t x, uint8_t y)
|
||||
{
|
||||
// return value
|
||||
int16_t val = 0;
|
||||
|
||||
// These are exception indicies
|
||||
if(x <= 6 || x >= 34)
|
||||
{
|
||||
// If the x index is in the upper range we need to translate it
|
||||
// to match the 10 indicies in the exceptions lookup table
|
||||
if(x >= 34) x -= 27;
|
||||
|
||||
// Read the unsigned value from the array
|
||||
val = (uint8_t)pgm_read_byte_far(&exceptions[x][y]);
|
||||
|
||||
// Read the 8 bit compressed sign values
|
||||
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))
|
||||
val = -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
|
||||
// original array (0-6) to the exception array, all the indicies
|
||||
// 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
|
||||
if(x >= 7) x -= 7;
|
||||
|
||||
// Init vars
|
||||
row_value stval;
|
||||
int16_t val = declination_keys.row_start[x], offset = 0;
|
||||
int8_t offset = 0;
|
||||
|
||||
// These will never exceed the second dimension length of 73
|
||||
uint8_t current_virtual_index = 0, r;
|
||||
|
||||
// This could be the length of the array or less (1075 or less)
|
||||
uint16_t start_index = 0, i;
|
||||
|
||||
// Init value to row start
|
||||
val = declination_keys.row_start[x];
|
||||
|
||||
// Find the first element in the 1D array
|
||||
// that corresponds with the target row
|
||||
|
Loading…
Reference in New Issue
Block a user