AP_Beacon_Pozyx.h 1.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344
  1. #pragma once
  2. #include "AP_Beacon_Backend.h"
  3. #define AP_BEACON_POZYX_MSG_LEN_MAX 20 // messages from uno/pozyx are no more than 20bytes
  4. #define AP_BEACON_POZYX_HEADER 0x01 // messages start with this character
  5. #define AP_BEACON_POZYX_MSGID_BEACON_CONFIG 0x02 // message contains anchor config information
  6. #define AP_BEACON_POZYX_MSGID_BEACON_DIST 0x03 // message contains individual beacon distance
  7. #define AP_BEACON_POZYX_MSGID_POSITION 0x04 // message contains vehicle position information
  8. #define AP_BEACON_DISTANCE_MAX 200.0f // sanity check beacon and vehicle messages to be within this distance from origin
  9. class AP_Beacon_Pozyx : public AP_Beacon_Backend
  10. {
  11. public:
  12. // constructor
  13. AP_Beacon_Pozyx(AP_Beacon &frontend, AP_SerialManager &serial_manager);
  14. // return true if sensor is basically healthy (we are receiving data)
  15. bool healthy() override;
  16. // update
  17. void update() override;
  18. private:
  19. enum ParseState{
  20. ParseState_WaitingForHeader = 0,
  21. ParseState_WaitingForMsgId = 1,
  22. ParseState_WaitingForLen = 2,
  23. ParseState_WaitingForContents = 3
  24. } parse_state;
  25. // parse buffer
  26. void parse_buffer();
  27. uint8_t parse_msg_id;
  28. uint8_t parse_msg_len;
  29. AP_HAL::UARTDriver *uart = nullptr;
  30. uint8_t linebuf[AP_BEACON_POZYX_MSG_LEN_MAX];
  31. uint8_t linebuf_len = 0;
  32. uint32_t last_update_ms = 0;
  33. };