/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see .
*/
#include "AP_Beacon_Pozyx.h"
#if AP_BEACON_POZYX_ENABLED
#include
#include
#include
extern const AP_HAL::HAL& hal;
// return true if sensor is basically healthy (we are receiving data)
bool AP_Beacon_Pozyx::healthy()
{
// healthy if we have parsed a message within the past 300ms
return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);
}
// update the state of the sensor
void AP_Beacon_Pozyx::update(void)
{
if (uart == nullptr) {
return;
}
// read any available characters
int16_t nbytes = uart->available();
while (nbytes-- > 0) {
char c = uart->read();
switch (parse_state) {
default:
case ParseState_WaitingForHeader:
if (c == AP_BEACON_POZYX_HEADER) {
parse_state = ParseState_WaitingForMsgId;
linebuf_len = 0;
}
break;
case ParseState_WaitingForMsgId:
parse_msg_id = c;
switch (parse_msg_id) {
case AP_BEACON_POZYX_MSGID_BEACON_CONFIG:
case AP_BEACON_POZYX_MSGID_BEACON_DIST:
case AP_BEACON_POZYX_MSGID_POSITION:
parse_state = ParseState_WaitingForLen;
break;
default:
// invalid message id
parse_state = ParseState_WaitingForHeader;
break;
}
break;
case ParseState_WaitingForLen:
parse_msg_len = c;
if (parse_msg_len > AP_BEACON_POZYX_MSG_LEN_MAX) {
// invalid message length
parse_state = ParseState_WaitingForHeader;
} else {
parse_state = ParseState_WaitingForContents;
}
break;
case ParseState_WaitingForContents:
// add to buffer
linebuf[linebuf_len++] = c;
if ((linebuf_len == parse_msg_len) || (linebuf_len == sizeof(linebuf))) {
// process buffer
parse_buffer();
// reset state for next message
parse_state = ParseState_WaitingForHeader;
}
break;
}
}
}
// parse buffer
void AP_Beacon_Pozyx::parse_buffer()
{
// check crc
uint8_t checksum = 0;
checksum ^= parse_msg_id;
checksum ^= parse_msg_len;
for (uint8_t i=0; i