123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include "AP_GPS.h"
- #include "GPS_Backend.h"
- class AP_GPS_ERB : public AP_GPS_Backend
- {
- public:
- using AP_GPS_Backend::AP_GPS_Backend;
-
- bool read() override;
- AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
- bool supports_mavlink_gps_rtk_message() override { return true; }
- static bool _detect(struct ERB_detect_state &state, uint8_t data);
- const char *name() const override { return "ERB"; }
- private:
- struct PACKED erb_header {
- uint8_t preamble1;
- uint8_t preamble2;
- uint8_t msg_id;
- uint16_t length;
- };
- struct PACKED erb_ver {
- uint32_t time;
- uint8_t ver_high;
- uint8_t ver_medium;
- uint8_t ver_low;
- };
- struct PACKED erb_pos {
- uint32_t time;
- double longitude;
- double latitude;
- double altitude_ellipsoid;
- double altitude_msl;
- uint32_t horizontal_accuracy;
- uint32_t vertical_accuracy;
- };
- struct PACKED erb_stat {
- uint32_t time;
- uint16_t week;
- uint8_t fix_type;
- uint8_t fix_status;
- uint8_t satellites;
- };
- struct PACKED erb_dops {
- uint32_t time;
- uint16_t gDOP;
- uint16_t pDOP;
- uint16_t vDOP;
- uint16_t hDOP;
- };
- struct PACKED erb_vel {
- uint32_t time;
- int32_t vel_north;
- int32_t vel_east;
- int32_t vel_down;
- uint32_t speed_2d;
- int32_t heading_2d;
- uint32_t speed_accuracy;
- };
- struct PACKED erb_rtk {
- uint8_t base_num_sats;
- uint16_t age_cs;
- int32_t baseline_N_mm;
- int32_t baseline_E_mm;
- int32_t baseline_D_mm;
- uint16_t ar_ratio;
- uint16_t base_week_number;
- uint32_t base_time_week_ms;
- };
-
- union PACKED {
- DEFINE_BYTE_ARRAY_METHODS
- erb_ver ver;
- erb_pos pos;
- erb_stat stat;
- erb_dops dops;
- erb_vel vel;
- erb_rtk rtk;
- } _buffer;
- enum erb_protocol_bytes {
- PREAMBLE1 = 0x45,
- PREAMBLE2 = 0x52,
- MSG_VER = 0x01,
- MSG_POS = 0x02,
- MSG_STAT = 0x03,
- MSG_DOPS = 0x04,
- MSG_VEL = 0x05,
- MSG_RTK = 0x07,
- };
- enum erb_fix_type {
- FIX_NONE = 0x00,
- FIX_SINGLE = 0x01,
- FIX_FLOAT = 0x02,
- FIX_FIX = 0x03,
- };
-
- uint8_t _ck_a;
- uint8_t _ck_b;
-
- uint8_t _step;
- uint8_t _msg_id;
- uint16_t _payload_length;
- uint16_t _payload_counter;
-
- uint8_t _fix_count;
- uint32_t _last_pos_time;
- uint32_t _last_vel_time;
-
- bool _new_position:1;
-
- bool _new_speed:1;
-
- bool _parse_gps();
-
- AP_GPS::GPS_Status next_fix = AP_GPS::NO_FIX;
- };
|