2010-09-06 06:20:44 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
2010-09-06 17:00:57 -03:00
|
|
|
//
|
|
|
|
// DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega.
|
|
|
|
// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
|
|
|
|
//
|
|
|
|
// This library is free software; you can redistribute it and / or
|
|
|
|
// modify it under the terms of the GNU Lesser General Public
|
|
|
|
// License as published by the Free Software Foundation; either
|
|
|
|
// version 2.1 of the License, or (at your option) any later version.
|
|
|
|
//
|
|
|
|
// GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.1"
|
|
|
|
//
|
2010-12-24 02:35:09 -04:00
|
|
|
// Note - see AP_GPS_MTK16.h for firmware 1.6 and later.
|
|
|
|
//
|
2012-09-27 02:18:44 -03:00
|
|
|
#ifndef __AP_GPS_MTK_H__
|
|
|
|
#define __AP_GPS_MTK_H__
|
2010-08-24 01:13:27 -03:00
|
|
|
|
2011-04-30 23:05:17 -03:00
|
|
|
#include "GPS.h"
|
2010-12-24 02:35:09 -04:00
|
|
|
#include "AP_GPS_MTK_Common.h"
|
2010-09-06 02:05:52 -03:00
|
|
|
|
2010-09-06 17:00:57 -03:00
|
|
|
class AP_GPS_MTK : public GPS {
|
|
|
|
public:
|
2012-12-17 22:31:05 -04:00
|
|
|
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
2012-08-17 03:19:44 -03:00
|
|
|
virtual bool read(void);
|
2012-09-17 01:43:07 -03:00
|
|
|
static bool _detect(uint8_t );
|
2010-09-06 17:00:57 -03:00
|
|
|
|
|
|
|
private:
|
2013-01-04 04:39:15 -04:00
|
|
|
#pragma pack(push,1)
|
2011-10-28 15:52:50 -03:00
|
|
|
struct diyd_mtk_msg {
|
2012-08-17 03:19:44 -03: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_time;
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2013-01-04 04:39:15 -04:00
|
|
|
#pragma pack(pop)
|
2011-10-28 15:52:50 -03:00
|
|
|
enum diyd_mtk_fix_type {
|
|
|
|
FIX_NONE = 1,
|
|
|
|
FIX_2D = 2,
|
2012-12-14 22:47:35 -04:00
|
|
|
FIX_3D = 3
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2010-09-06 17:00:57 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
enum diyd_mtk_protocol_bytes {
|
|
|
|
PREAMBLE1 = 0xb5,
|
|
|
|
PREAMBLE2 = 0x62,
|
|
|
|
MESSAGE_CLASS = 1,
|
|
|
|
MESSAGE_ID = 5
|
|
|
|
};
|
2010-09-06 17:00:57 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// Packet checksum accumulators
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _ck_a;
|
|
|
|
uint8_t _ck_b;
|
2010-09-06 17:00:57 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// State machine state
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _step;
|
|
|
|
uint8_t _payload_counter;
|
2010-09-06 17:00:57 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// Receive buffer
|
|
|
|
union {
|
2012-08-17 03:19:44 -03:00
|
|
|
diyd_mtk_msg msg;
|
|
|
|
uint8_t bytes[];
|
2011-10-28 15:52:50 -03:00
|
|
|
} _buffer;
|
2010-09-06 17:00:57 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// Buffer parse & GPS state update
|
2012-08-17 03:19:44 -03:00
|
|
|
void _parse_gps();
|
2010-08-24 01:13:27 -03:00
|
|
|
};
|
2010-09-06 17:00:57 -03:00
|
|
|
|
2012-09-27 02:18:44 -03:00
|
|
|
#endif // __AP_GPS_MTK_H__
|