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-08-24 01:13:27 -03:00
|
|
|
#ifndef AP_GPS_MTK_h
|
|
|
|
#define AP_GPS_MTK_h
|
|
|
|
|
2010-08-29 19:08:33 -03:00
|
|
|
#include <GPS.h>
|
2010-08-24 01:13:27 -03:00
|
|
|
#define MAXPAYLOAD 32
|
|
|
|
|
2010-09-06 06:20:44 -03:00
|
|
|
#define MTK_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n"
|
|
|
|
#define MTK_SET_NMEA "$PGCMD,16,1,1,1,1,1*6B\r\n"
|
2010-09-06 02:05:52 -03:00
|
|
|
|
2010-09-06 06:20:44 -03:00
|
|
|
#define MTK_OUTPUT_1HZ "$PMTK220,1000*1F\r\n"
|
|
|
|
#define MTK_OUTPUT_2HZ "$PMTK220,500*2B\r\n"
|
|
|
|
#define MTK_OUTPUT_4HZ "$PMTK220,250*29\r\n"
|
|
|
|
#define MTK_OTUPUT_5HZ "$PMTK220,200*2C\r\n"
|
|
|
|
#define MTK_OUTPUT_10HZ "$PMTK220,100*2F\r\n"
|
2010-09-06 02:05:52 -03:00
|
|
|
|
|
|
|
#define MTK_BAUD_RATE_38400 "$PMTK251,38400*27\r\n"
|
|
|
|
|
2010-09-06 06:20:44 -03:00
|
|
|
#define SBAS_ON "$PMTK313,1*2E\r\n"
|
|
|
|
#define SBAS_OFF "$PMTK313,0*2F\r\n"
|
2010-09-06 02:05:52 -03:00
|
|
|
|
2010-09-06 06:20:44 -03:00
|
|
|
#define WAAS_ON "$PSRF151,1*3F\r\n"
|
|
|
|
#define WAAS_OFF "$PSRF151,0*3E\r\n"
|
2010-09-06 02:05:52 -03:00
|
|
|
|
2010-09-06 17:00:57 -03:00
|
|
|
class AP_GPS_MTK : public GPS {
|
|
|
|
public:
|
2010-09-06 06:20:44 -03:00
|
|
|
AP_GPS_MTK(Stream *s);
|
2010-10-17 03:06:04 -03:00
|
|
|
virtual void init(void);
|
2010-12-19 09:24:29 -04:00
|
|
|
virtual void read(void);
|
2010-09-06 17:00:57 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
#pragma pack(1)
|
|
|
|
struct 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;
|
|
|
|
};
|
|
|
|
#pragma pack(pop)
|
|
|
|
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
|
|
|
|
};
|
|
|
|
|
|
|
|
// Packet checksum accumulators
|
2010-09-06 19:30:29 -03:00
|
|
|
uint8_t _ck_a;
|
|
|
|
uint8_t _ck_b;
|
2010-09-06 17:00:57 -03:00
|
|
|
|
|
|
|
// State machine state
|
2010-09-06 19:30:29 -03:00
|
|
|
uint8_t _step;
|
|
|
|
uint8_t _payload_length;
|
|
|
|
uint8_t _payload_counter;
|
2010-09-06 17:00:57 -03:00
|
|
|
|
|
|
|
// Receive buffer
|
|
|
|
union {
|
|
|
|
diyd_mtk_msg msg;
|
|
|
|
uint8_t bytes[];
|
2010-09-06 19:30:29 -03:00
|
|
|
} _buffer;
|
2010-09-06 17:00:57 -03:00
|
|
|
|
|
|
|
// Buffer parse & GPS state update
|
|
|
|
void _parse_gps();
|
2010-08-24 01:13:27 -03:00
|
|
|
};
|
2010-09-06 17:00:57 -03:00
|
|
|
|
|
|
|
#endif // AP_GPS_MTK_H
|