Path: blob/master/libraries/AP_Beacon/AP_Beacon_Pozyx.h
9775 views
#pragma once12#include "AP_Beacon_Backend.h"34#if AP_BEACON_POZYX_ENABLED56#define AP_BEACON_POZYX_MSG_LEN_MAX 20 // messages from uno/pozyx are no more than 20bytes7#define AP_BEACON_POZYX_HEADER 0x01 // messages start with this character8#define AP_BEACON_POZYX_MSGID_BEACON_CONFIG 0x02 // message contains anchor config information9#define AP_BEACON_POZYX_MSGID_BEACON_DIST 0x03 // message contains individual beacon distance10#define AP_BEACON_POZYX_MSGID_POSITION 0x04 // message contains vehicle position information11#define AP_BEACON_DISTANCE_MAX 200.0f // sanity check beacon and vehicle messages to be within this distance from origin1213class AP_Beacon_Pozyx : public AP_Beacon_Backend14{1516public:17// constructor18using AP_Beacon_Backend::AP_Beacon_Backend;1920// return true if sensor is basically healthy (we are receiving data)21bool healthy() override;2223// update24void update() override;2526private:2728enum ParseState{29ParseState_WaitingForHeader = 0,30ParseState_WaitingForMsgId = 1,31ParseState_WaitingForLen = 2,32ParseState_WaitingForContents = 333} parse_state;3435// parse buffer36void parse_buffer();3738uint8_t parse_msg_id;39uint8_t parse_msg_len;4041uint8_t linebuf[AP_BEACON_POZYX_MSG_LEN_MAX];42uint8_t linebuf_len = 0;43uint32_t last_update_ms = 0;44};4546#endif // AP_BEACON_POZYX_ENABLED474849