APM:Libraries
AP_Beacon_Pozyx.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Beacon_Backend.h"
4 
5 #define AP_BEACON_POZYX_MSG_LEN_MAX 20 // messages from uno/pozyx are no more than 20bytes
6 #define AP_BEACON_POZYX_HEADER 0x01 // messages start with this character
7 #define AP_BEACON_POZYX_MSGID_BEACON_CONFIG 0x02 // message contains anchor config information
8 #define AP_BEACON_POZYX_MSGID_BEACON_DIST 0x03 // message contains individual beacon distance
9 #define AP_BEACON_POZYX_MSGID_POSITION 0x04 // message contains vehicle position information
10 #define AP_BEACON_DISTANCE_MAX 200.0f // sanity check beacon and vehicle messages to be within this distance from origin
11 
13 {
14 
15 public:
16  // constructor
18 
19  // return true if sensor is basically healthy (we are receiving data)
20  bool healthy();
21 
22  // update
23  void update();
24 
25 private:
26 
27  enum ParseState{
32  } parse_state;
33 
34  // parse buffer
35  void parse_buffer();
36 
37  uint8_t parse_msg_id;
38  uint8_t parse_msg_len;
39 
42  uint8_t linebuf_len = 0;
43  uint32_t last_update_ms = 0;
44 };
uint8_t linebuf[AP_BEACON_POZYX_MSG_LEN_MAX]
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
AP_Beacon_Pozyx(AP_Beacon &frontend, AP_SerialManager &serial_manager)
AP_HAL::UARTDriver * uart
uint32_t last_update_ms
#define AP_BEACON_POZYX_MSG_LEN_MAX
enum AP_Beacon_Pozyx::ParseState parse_state