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/>.
|
|
|
|
*/
|
|
|
|
|
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
|
|
|
|
//
|
|
|
|
// GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.1"
|
|
|
|
//
|
2010-08-24 01:13:27 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_GPS.h"
|
2012-09-27 02:18:44 -03:00
|
|
|
#include "AP_GPS_MTK.h"
|
|
|
|
|
2014-03-31 06:48:22 -03:00
|
|
|
// initialisation blobs to send to the GPS to try to get it into the
|
|
|
|
// right mode
|
2015-10-26 08:25:44 -03:00
|
|
|
const char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF;
|
2014-03-31 06:48:22 -03:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
|
|
|
|
AP_GPS_Backend(_gps, _state, _port),
|
|
|
|
_step(0),
|
|
|
|
_payload_counter(0)
|
2011-10-28 15:52:50 -03:00
|
|
|
{
|
2014-03-31 06:48:22 -03:00
|
|
|
gps.send_blob_start(state.instance, _initialisation_blob, sizeof(_initialisation_blob));
|
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
|
2014-03-31 06:48:22 -03:00
|
|
|
/*
|
|
|
|
send an initialisation blob to configure the GPS
|
|
|
|
*/
|
|
|
|
void AP_GPS_MTK::send_init_blob(uint8_t instance, AP_GPS &gps)
|
|
|
|
{
|
|
|
|
gps.send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
2010-08-24 01:13:27 -03:00
|
|
|
}
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
|
2010-09-06 17:00:57 -03: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.
|
|
|
|
//
|
2010-12-24 02:35:09 -04:00
|
|
|
bool
|
|
|
|
AP_GPS_MTK::read(void)
|
2010-08-24 01:13:27 -03:00
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
uint8_t data;
|
|
|
|
int16_t numc;
|
|
|
|
bool parsed = false;
|
2011-10-28 15:52:50 -03:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
numc = port->available();
|
2012-08-21 23:19:51 -03:00
|
|
|
for (int16_t i = 0; i < numc; i++) { // Process bytes received
|
2011-10-28 15:52:50 -03:00
|
|
|
|
|
|
|
// read the next byte
|
2014-03-28 16:52:27 -03:00
|
|
|
data = port->read();
|
2011-10-28 15:52:50 -03:00
|
|
|
|
|
|
|
restart:
|
|
|
|
switch(_step) {
|
|
|
|
|
2012-08-21 23:19:51 -03: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.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 0:
|
|
|
|
if(PREAMBLE1 == data)
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
case 1:
|
|
|
|
if (PREAMBLE2 == data) {
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
_step = 0;
|
|
|
|
goto restart;
|
|
|
|
case 2:
|
|
|
|
if (MESSAGE_CLASS == data) {
|
|
|
|
_step++;
|
2012-08-21 23:19:51 -03:00
|
|
|
_ck_b = _ck_a = data; // reset the checksum accumulators
|
2011-10-28 15:52:50 -03:00
|
|
|
} else {
|
2012-08-21 23:19:51 -03:00
|
|
|
_step = 0; // reset and wait for a message of the right class
|
2011-10-28 15:52:50 -03:00
|
|
|
goto restart;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
if (MESSAGE_ID == data) {
|
|
|
|
_step++;
|
|
|
|
_ck_b += (_ck_a += data);
|
|
|
|
_payload_counter = 0;
|
|
|
|
} else {
|
|
|
|
_step = 0;
|
|
|
|
goto restart;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Receive message data
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 4:
|
2016-06-06 10:49:46 -03:00
|
|
|
_buffer[_payload_counter++] = data;
|
2011-10-28 15:52:50 -03:00
|
|
|
_ck_b += (_ck_a += data);
|
|
|
|
if (_payload_counter == sizeof(_buffer))
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Checksum and message processing
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 5:
|
|
|
|
_step++;
|
|
|
|
if (_ck_a != data) {
|
|
|
|
_step = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 6:
|
|
|
|
_step = 0;
|
|
|
|
if (_ck_b != data) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2013-03-25 04:24:14 -03:00
|
|
|
// set fix type
|
|
|
|
if (_buffer.msg.fix_type == FIX_3D) {
|
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) {
|
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
|
|
|
}
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.lat = swap_int32(_buffer.msg.latitude) * 10;
|
|
|
|
state.location.lng = swap_int32(_buffer.msg.longitude) * 10;
|
|
|
|
state.location.alt = swap_int32(_buffer.msg.altitude);
|
|
|
|
state.ground_speed = swap_int32(_buffer.msg.ground_speed) * 0.01f;
|
2016-05-04 22:28:35 -03:00
|
|
|
state.ground_course = wrap_360(swap_int32(_buffer.msg.ground_course) * 1.0e-6f);
|
2014-03-28 16:52:27 -03:00
|
|
|
state.num_sats = _buffer.msg.satellites;
|
|
|
|
|
|
|
|
if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
|
|
|
|
make_gps_time(0, swap_int32(_buffer.msg.utc_time)*10);
|
2013-10-23 08:13:48 -03:00
|
|
|
}
|
|
|
|
// we don't change _last_gps_time as we don't know the
|
|
|
|
// full date
|
2011-10-28 15:52:50 -03:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
fill_3d_velocity();
|
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
parsed = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return parsed;
|
2010-08-24 01:13:27 -03:00
|
|
|
}
|
2012-09-17 01:43:07 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
detect a MTK GPS
|
|
|
|
*/
|
|
|
|
bool
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_MTK::_detect(struct MTK_detect_state &state, uint8_t data)
|
2012-09-17 01:43:07 -03:00
|
|
|
{
|
2014-03-28 00:50:44 -03:00
|
|
|
switch (state.step) {
|
2012-09-17 01:43:07 -03:00
|
|
|
case 1:
|
|
|
|
if (PREAMBLE2 == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
}
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2017-08-22 14:28:10 -03:00
|
|
|
FALLTHROUGH;
|
2012-09-17 01:43:07 -03:00
|
|
|
case 0:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.ck_b = state.ck_a = state.payload_counter = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
if(PREAMBLE1 == data)
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 2:
|
|
|
|
if (MESSAGE_CLASS == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b = state.ck_a = data;
|
2012-09-17 01:43:07 -03:00
|
|
|
} else {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
if (MESSAGE_ID == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
state.ck_b += (state.ck_a += data);
|
|
|
|
state.payload_counter = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
} else {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 4:
|
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-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
case 5:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
|
|
|
if (state.ck_a != data) {
|
|
|
|
state.step = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 6:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
|
|
|
if (state.ck_b == data) {
|
2012-09-17 01:43:07 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|