2013-05-29 20:52:21 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2012-12-14 22:47:35 -04:00
|
|
|
//
|
|
|
|
// DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega.
|
|
|
|
// Code by Michael Smith, Jordi Munoz and Jose Julio, Craig Elder, DIYDrones.com
|
|
|
|
//
|
|
|
|
// GPS configuration : Custom protocol per "Customize Function Specification, 3D Robotics, v1.6, v1.7, v1.8, v1.9"
|
|
|
|
//
|
2016-02-17 21:25:23 -04:00
|
|
|
#pragma once
|
2012-12-14 22:47:35 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_GPS.h"
|
2012-12-14 22:47:35 -04:00
|
|
|
#include "AP_GPS_MTK_Common.h"
|
|
|
|
|
|
|
|
#define MTK_GPS_REVISION_V16 16
|
|
|
|
#define MTK_GPS_REVISION_V19 19
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
class AP_GPS_MTK19 : public AP_GPS_Backend {
|
2012-12-14 22:47:35 -04:00
|
|
|
public:
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
2013-02-19 20:32:15 -04:00
|
|
|
|
2014-03-28 00:50:44 -03:00
|
|
|
bool read(void);
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
static bool _detect(struct MTK19_detect_state &state, uint8_t data);
|
2012-12-14 22:47:35 -04:00
|
|
|
|
|
|
|
private:
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED diyd_mtk_msg {
|
2012-12-14 22:47:35 -04:00
|
|
|
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,
|
2013-01-01 23:43:33 -04:00
|
|
|
PREAMBLE2 = 0xdd,
|
2012-12-14 22:47:35 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
// Packet checksum accumulators
|
|
|
|
uint8_t _ck_a;
|
|
|
|
uint8_t _ck_b;
|
|
|
|
|
|
|
|
// State machine state
|
|
|
|
uint8_t _step;
|
|
|
|
uint8_t _payload_counter;
|
2013-01-01 23:43:33 -04:00
|
|
|
uint8_t _mtk_revision;
|
2012-12-14 22:47:35 -04:00
|
|
|
|
2013-10-23 08:13:48 -03:00
|
|
|
uint8_t _fix_counter;
|
2012-12-14 22:47:35 -04:00
|
|
|
|
|
|
|
// Receive buffer
|
|
|
|
union {
|
|
|
|
diyd_mtk_msg msg;
|
|
|
|
uint8_t bytes[];
|
|
|
|
} _buffer;
|
|
|
|
};
|