mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: Make the char_to_hex method a common method
This commit is contained in:
parent
1e91dfe9d6
commit
511dec01c5
|
@ -197,14 +197,3 @@ bool AP_WindVane_NMEA::decode_latest_term()
|
|||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// return the numeric value of an ascii hex character
|
||||
int16_t AP_WindVane_NMEA::char_to_hex(char a)
|
||||
{
|
||||
if (a >= 'A' && a <= 'F')
|
||||
return a - 'A' + 10;
|
||||
else if (a >= 'a' && a <= 'f')
|
||||
return a - 'a' + 10;
|
||||
else
|
||||
return a - '0';
|
||||
}
|
||||
|
|
|
@ -42,9 +42,6 @@ private:
|
|||
// decode each term
|
||||
bool decode_latest_term();
|
||||
|
||||
// convert from char to hex value for checksum
|
||||
int16_t char_to_hex(char a);
|
||||
|
||||
// latest values read in
|
||||
float _speed_ms;
|
||||
float _wind_dir_deg;
|
||||
|
|
Loading…
Reference in New Issue