AP_Common: Make hexadecimal character number conversion method common

This commit is contained in:
murata 2019-07-12 10:52:37 +02:00 committed by Andrew Tridgell
parent 0dfb1e858c
commit a39228c453
2 changed files with 36 additions and 0 deletions

View File

@ -36,3 +36,37 @@ bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound)
return false;
}
/**
* return the numeric value of an ascii hex character
*
* @param [in] a Hexa character
* @param [out] res uint8 value
* @retval true Conversion OK
* @retval false Input value error
* @Note Input character is 0-9, A-F, a-f
* A 0x41, a 0x61, 0 0x30
*/
bool hex_to_uint8(uint8_t a, uint8_t &res)
{
uint8_t nibble_low = a & 0xf;
switch (a & 0xf0) {
case 0x30: // 0-
if (nibble_low > 9) {
return false;
}
res = nibble_low;
break;
case 0x40: // uppercase A-
case 0x60: // lowercase a-
if (nibble_low == 0 || nibble_low > 6) {
return false;
}
res = nibble_low + 9;
break;
default:
return false;
}
return true;
}

View File

@ -133,3 +133,5 @@ template<typename s, size_t t> struct assert_storage_size {
False otherwise.
*/
bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound);
bool hex_to_uint8(uint8_t a, uint8_t &res); // return the uint8 value of an ascii hex character