mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_WindVane_NMEA: decode each sentence once
This commit is contained in:
parent
2adbaf1a1d
commit
89217a3804
@ -86,6 +86,10 @@ bool AP_WindVane_NMEA::decode(char c)
|
||||
case '\n':
|
||||
case '*':
|
||||
{
|
||||
if (_sentence_done) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// null terminate and decode latest term
|
||||
_term[_term_offset] = 0;
|
||||
bool valid_sentence = decode_latest_term();
|
||||
@ -105,6 +109,7 @@ bool AP_WindVane_NMEA::decode(char c)
|
||||
_term_is_checksum = false;
|
||||
_wind_dir_deg = -1.0f;
|
||||
_speed_ms = -1.0f;
|
||||
_sentence_done = false;
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -125,6 +130,7 @@ bool AP_WindVane_NMEA::decode_latest_term()
|
||||
{
|
||||
// handle the last term in a message
|
||||
if (_term_is_checksum) {
|
||||
_sentence_done = true;
|
||||
uint8_t checksum = 16 * char_to_hex(_term[0]) + char_to_hex(_term[1]);
|
||||
return ((checksum == _checksum) && _sentence_valid);
|
||||
}
|
||||
|
@ -55,4 +55,5 @@ private:
|
||||
uint8_t _checksum; // checksum accumulator
|
||||
bool _term_is_checksum; // current term is the checksum
|
||||
bool _sentence_valid; // is current sentence valid so far
|
||||
bool _sentence_done; // true if this sentence has already been decoded
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user