1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283 |
- #pragma once
- #include "AP_GPS.h"
- #include "GPS_Backend.h"
- #include "AP_GPS_MTK_Common.h"
- class AP_GPS_MTK : public AP_GPS_Backend {
- public:
- AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
- bool read(void) override;
- static bool _detect(struct MTK_detect_state &state, uint8_t data);
- static void send_init_blob(uint8_t instance, AP_GPS &gps);
- const char *name() const override { return "MTK"; }
- 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_time;
- };
- enum diyd_mtk_fix_type {
- FIX_NONE = 1,
- FIX_2D = 2,
- FIX_3D = 3
- };
- enum diyd_mtk_protocol_bytes {
- PREAMBLE1 = 0xb5,
- PREAMBLE2 = 0x62,
- MESSAGE_CLASS = 1,
- MESSAGE_ID = 5
- };
-
- uint8_t _ck_a;
- uint8_t _ck_b;
-
- uint8_t _step;
- uint8_t _payload_counter;
-
- union PACKED {
- DEFINE_BYTE_ARRAY_METHODS
- diyd_mtk_msg msg;
- } _buffer;
-
- void _parse_gps();
- static const char _initialisation_blob[];
- };
|