123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384 |
- #pragma once
- #include "AP_GPS.h"
- #include "GPS_Backend.h"
- #include "AP_GPS_MTK_Common.h"
- #define MTK_GPS_REVISION_V16 16
- #define MTK_GPS_REVISION_V19 19
- class AP_GPS_MTK19 : public AP_GPS_Backend {
- public:
- AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
- bool read(void) override;
- static bool _detect(struct MTK19_detect_state &state, uint8_t data);
- const char *name() const override { return "MTK19"; }
- private:
- struct PACKED diyd_mtk_msg {
- int32_t latitude;
- int32_t longitude;
- int32_t altitude;
- int32_t ground_speed;
- int32_t ground_course;
- uint8_t satellites;
- uint8_t fix_type;
- uint32_t utc_date;
- uint32_t utc_time;
- uint16_t hdop;
- };
- enum diyd_mtk_fix_type {
- FIX_NONE = 1,
- FIX_2D = 2,
- FIX_3D = 3,
- FIX_2D_SBAS = 6,
- FIX_3D_SBAS = 7
- };
- enum diyd_mtk_protocol_bytes {
- PREAMBLE1_V16 = 0xd0,
- PREAMBLE1_V19 = 0xd1,
- PREAMBLE2 = 0xdd,
- };
-
- uint8_t _ck_a;
- uint8_t _ck_b;
-
- uint8_t _step;
- uint8_t _payload_counter;
- uint8_t _mtk_revision;
- uint8_t _fix_counter;
-
- union {
- DEFINE_BYTE_ARRAY_METHODS
- diyd_mtk_msg msg;
- } _buffer;
- };
|