UAVCAN: change hex2nibble method to use branching instead of plain lookup table
This commit is contained in:
parent
2c0521654c
commit
38125ab92a
@ -44,27 +44,26 @@ static bool hex2nibble_error;
|
||||
static uint8_t hex2nibble(char ch)
|
||||
{
|
||||
// Must go into RAM, not flash, because flash is slow
|
||||
static uint8_t ConversionTable[] =
|
||||
static uint8_t NumConversionTable[] =
|
||||
{
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255,
|
||||
0, 1, 2, 3, 4, 5, 6, 7, 8, 9, // 0..9
|
||||
255, 255, 255, 255, 255, 255, 255,
|
||||
10, 11, 12, 13, 14, 15, // A..F
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255,
|
||||
10, 11, 12, 13, 14, 15, // a..f
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
|
||||
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255
|
||||
0, 1, 2, 3, 4, 5, 6, 7, 8, 9
|
||||
};
|
||||
|
||||
const uint8_t out = ConversionTable[int(ch)];
|
||||
static uint8_t AlphaConversionTable[] =
|
||||
{
|
||||
10, 11, 12, 13, 14, 15
|
||||
};
|
||||
|
||||
uint8_t out = 255;
|
||||
|
||||
if (ch >= '0' && ch <= '9') {
|
||||
out = NumConversionTable[int(ch) - int('0')];
|
||||
} else if (ch >= 'a' && ch <= 'f') {
|
||||
out = AlphaConversionTable[int(ch) - int('a')];
|
||||
} else if (ch >= 'A' && ch <= 'F') {
|
||||
out = AlphaConversionTable[int(ch) - int('A')];
|
||||
}
|
||||
|
||||
if (out == 255)
|
||||
{
|
||||
hex2nibble_error = true;
|
||||
|
Loading…
Reference in New Issue
Block a user