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.
|
2012-12-20 19:47:09 -04:00
|
|
|
// Code by Michael Smith, Jordi Munoz and Jose Julio, Craig Elder, DIYDrones.com
|
2012-12-14 22:47:35 -04:00
|
|
|
//
|
2012-12-20 19:47:09 -04:00
|
|
|
// GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.6, v1.7, v1.8, v1.9"
|
2012-12-14 22:47:35 -04:00
|
|
|
//
|
2013-02-16 07:03:53 -04:00
|
|
|
// Note that this driver supports both the 1.6 and 1.9 protocol varients
|
|
|
|
//
|
2012-12-14 22:47:35 -04:00
|
|
|
|
|
|
|
#include "AP_GPS_MTK19.h"
|
|
|
|
|
2013-10-23 08:13:48 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_MTK19::AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
|
|
|
AP_GPS_Backend(_gps, _state, _port),
|
|
|
|
_step(0),
|
|
|
|
_payload_counter(0),
|
|
|
|
_mtk_revision(0),
|
|
|
|
_fix_counter(0)
|
2012-12-14 22:47:35 -04:00
|
|
|
{
|
2014-03-31 06:48:22 -03:00
|
|
|
AP_GPS_MTK::send_init_blob(_state.instance, _gps);
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// Process bytes available from the stream
|
|
|
|
//
|
|
|
|
// The stream is assumed to contain only our custom message. If it
|
|
|
|
// contains other messages, and those messages contain the preamble bytes,
|
|
|
|
// it is possible for this code to become de-synchronised. Without
|
|
|
|
// buffering the entire message and re-processing it from the top,
|
|
|
|
// this is unavoidable.
|
|
|
|
//
|
|
|
|
// The lack of a standard header length field makes it impossible to skip
|
|
|
|
// unrecognised messages.
|
|
|
|
//
|
|
|
|
bool
|
|
|
|
AP_GPS_MTK19::read(void)
|
|
|
|
{
|
|
|
|
uint8_t data;
|
|
|
|
int16_t numc;
|
|
|
|
bool parsed = false;
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
numc = port->available();
|
2012-12-14 22:47:35 -04:00
|
|
|
for (int16_t i = 0; i < numc; i++) { // Process bytes received
|
|
|
|
|
|
|
|
// read the next byte
|
2014-03-28 16:52:27 -03:00
|
|
|
data = port->read();
|
2012-12-14 22:47:35 -04:00
|
|
|
|
|
|
|
restart:
|
2012-12-20 19:47:09 -04:00
|
|
|
switch(_step) {
|
2012-12-14 22:47:35 -04:00
|
|
|
|
|
|
|
// Message preamble, class, ID detection
|
|
|
|
//
|
|
|
|
// If we fail to match any of the expected bytes, we
|
|
|
|
// reset the state machine and re-consider the failed
|
|
|
|
// byte as the first byte of the preamble. This
|
|
|
|
// improves our chances of recovering from a mismatch
|
|
|
|
// and makes it less likely that we will be fooled by
|
|
|
|
// the preamble appearing as data in some other message.
|
|
|
|
//
|
|
|
|
case 0:
|
2012-12-20 19:47:09 -04:00
|
|
|
if (data == PREAMBLE1_V16) {
|
2013-01-01 23:43:33 -04:00
|
|
|
_mtk_revision = MTK_GPS_REVISION_V16;
|
2012-12-14 22:47:35 -04:00
|
|
|
_step++;
|
2013-01-01 23:43:33 -04:00
|
|
|
} else if (data == PREAMBLE1_V19) {
|
|
|
|
_mtk_revision = MTK_GPS_REVISION_V19;
|
2012-12-20 19:47:09 -04:00
|
|
|
_step++;
|
|
|
|
}
|
|
|
|
break;
|
2012-12-14 22:47:35 -04:00
|
|
|
case 1:
|
2013-01-01 23:43:33 -04:00
|
|
|
if (data == PREAMBLE2) {
|
2012-12-20 19:47:09 -04:00
|
|
|
_step++;
|
2013-01-01 19:12:55 -04:00
|
|
|
} else {
|
2013-01-01 23:43:33 -04:00
|
|
|
_step = 0;
|
2013-01-01 19:12:55 -04:00
|
|
|
goto restart;
|
|
|
|
}
|
|
|
|
break;
|
2012-12-14 22:47:35 -04:00
|
|
|
case 2:
|
|
|
|
if (sizeof(_buffer) == data) {
|
|
|
|
_step++;
|
2012-12-21 20:04:02 -04:00
|
|
|
_ck_b = _ck_a = data; // reset the checksum accumulators
|
2012-12-20 19:47:09 -04:00
|
|
|
_payload_counter = 0;
|
2012-12-14 22:47:35 -04:00
|
|
|
} else {
|
2012-12-20 19:47:09 -04:00
|
|
|
_step = 0; // reset and wait for a message of the right class
|
2013-01-01 19:12:55 -04:00
|
|
|
goto restart;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
// Receive message data
|
|
|
|
//
|
|
|
|
case 3:
|
|
|
|
_buffer.bytes[_payload_counter++] = data;
|
|
|
|
_ck_b += (_ck_a += data);
|
2013-01-04 04:40:49 -04:00
|
|
|
if (_payload_counter == sizeof(_buffer)) {
|
2012-12-14 22:47:35 -04:00
|
|
|
_step++;
|
2013-01-04 04:40:49 -04:00
|
|
|
}
|
2012-12-14 22:47:35 -04:00
|
|
|
break;
|
|
|
|
|
|
|
|
// Checksum and message processing
|
|
|
|
//
|
|
|
|
case 4:
|
|
|
|
_step++;
|
|
|
|
if (_ck_a != data) {
|
2012-12-20 19:47:09 -04:00
|
|
|
_step = 0;
|
2013-01-04 04:40:49 -04:00
|
|
|
goto restart;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 5:
|
2012-12-20 19:47:09 -04:00
|
|
|
_step = 0;
|
2012-12-14 22:47:35 -04:00
|
|
|
if (_ck_b != data) {
|
2013-01-04 04:40:49 -04:00
|
|
|
goto restart;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
|
2013-03-25 04:24:14 -03:00
|
|
|
// parse fix
|
|
|
|
if (_buffer.msg.fix_type == FIX_3D || _buffer.msg.fix_type == FIX_3D_SBAS) {
|
2014-03-28 16:52:27 -03:00
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
2013-03-25 04:24:14 -03:00
|
|
|
}else if (_buffer.msg.fix_type == FIX_2D || _buffer.msg.fix_type == FIX_2D_SBAS) {
|
2014-03-28 16:52:27 -03:00
|
|
|
state.status = AP_GPS::GPS_OK_FIX_2D;
|
2013-03-25 04:24:14 -03:00
|
|
|
}else{
|
2014-03-28 16:52:27 -03:00
|
|
|
state.status = AP_GPS::NO_FIX;
|
2013-03-25 04:24:14 -03:00
|
|
|
}
|
|
|
|
|
2013-01-01 23:43:33 -04:00
|
|
|
if (_mtk_revision == MTK_GPS_REVISION_V16) {
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.lat = _buffer.msg.latitude * 10; // V16, V17,V18 doc says *10e7 but device says otherwise
|
|
|
|
state.location.lng = _buffer.msg.longitude * 10; // V16, V17,V18 doc says *10e7 but device says otherwise
|
2013-01-01 23:43:33 -04:00
|
|
|
} else {
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.lat = _buffer.msg.latitude;
|
|
|
|
state.location.lng = _buffer.msg.longitude;
|
2013-01-01 23:43:33 -04:00
|
|
|
}
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.alt = _buffer.msg.altitude;
|
|
|
|
state.ground_speed = _buffer.msg.ground_speed*0.01f;
|
|
|
|
state.ground_course_cd = _buffer.msg.ground_course;
|
|
|
|
state.num_sats = _buffer.msg.satellites;
|
|
|
|
state.hdop = _buffer.msg.hdop;
|
2013-10-23 08:13:48 -03:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
|
2013-10-23 08:13:48 -03:00
|
|
|
if (_fix_counter == 0) {
|
|
|
|
uint32_t bcd_time_ms;
|
2015-03-12 20:29:36 -03:00
|
|
|
bcd_time_ms = _buffer.msg.utc_time;
|
|
|
|
#if 0
|
|
|
|
hal.console->printf("utc_date=%lu utc_time=%lu rev=%u\n",
|
|
|
|
(unsigned long)_buffer.msg.utc_date,
|
|
|
|
(unsigned long)_buffer.msg.utc_time,
|
|
|
|
(unsigned)_mtk_revision);
|
|
|
|
#endif
|
2014-03-28 16:52:27 -03:00
|
|
|
make_gps_time(_buffer.msg.utc_date, bcd_time_ms);
|
|
|
|
state.last_gps_time_ms = hal.scheduler->millis();
|
2013-10-23 08:13:48 -03:00
|
|
|
}
|
|
|
|
// the _fix_counter is to reduce the cost of the GPS
|
|
|
|
// BCD time conversion by only doing it every 10s
|
|
|
|
// between those times we use the HAL system clock as
|
|
|
|
// an offset from the last fix
|
|
|
|
_fix_counter++;
|
|
|
|
if (_fix_counter == 50) {
|
|
|
|
_fix_counter = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
fill_3d_velocity();
|
2012-12-14 22:47:35 -04:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
parsed = true;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
return parsed;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
2012-12-21 20:04:02 -04:00
|
|
|
detect a MTK16 or MTK19 GPS
|
2012-12-14 22:47:35 -04:00
|
|
|
*/
|
|
|
|
bool
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_MTK19::_detect(struct MTK19_detect_state &state, uint8_t data)
|
2012-12-14 22:47:35 -04:00
|
|
|
{
|
2013-01-01 19:12:55 -04:00
|
|
|
restart:
|
2014-03-28 00:50:44 -03:00
|
|
|
switch (state.step) {
|
2012-12-14 22:47:35 -04:00
|
|
|
case 0:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.ck_b = state.ck_a = state.payload_counter = 0;
|
2013-01-01 23:43:33 -04:00
|
|
|
if (data == PREAMBLE1_V16 || data == PREAMBLE1_V19) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-12-20 19:47:09 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 1:
|
2013-01-01 23:43:33 -04:00
|
|
|
if (PREAMBLE2 == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2013-01-01 19:12:55 -04:00
|
|
|
} else {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2013-01-01 19:12:55 -04:00
|
|
|
goto restart;
|
|
|
|
}
|
|
|
|
break;
|
2012-12-14 22:47:35 -04:00
|
|
|
case 2:
|
|
|
|
if (data == sizeof(struct diyd_mtk_msg)) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b = state.ck_a = data;
|
2012-12-14 22:47:35 -04:00
|
|
|
} else {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2013-01-04 04:40:49 -04:00
|
|
|
goto restart;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 3:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.ck_b += (state.ck_a += data);
|
|
|
|
if (++state.payload_counter == sizeof(struct diyd_mtk_msg))
|
|
|
|
state.step++;
|
2012-12-14 22:47:35 -04:00
|
|
|
break;
|
|
|
|
case 4:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
if (state.ck_a != data) {
|
|
|
|
state.step = 0;
|
2013-01-04 04:40:49 -04:00
|
|
|
goto restart;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 5:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
|
|
|
if (state.ck_b != data) {
|
2013-01-04 04:40:49 -04:00
|
|
|
goto restart;
|
|
|
|
}
|
|
|
|
return true;
|
2012-12-14 22:47:35 -04:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|