AP_GPS: remove mtk GPSs

These are ancient and of very poor quality.
This commit is contained in:
Peter Barker 2021-09-28 11:12:31 +10:00 committed by Andrew Tridgell
parent 6e9ea663e5
commit 068f91169c
9 changed files with 5 additions and 694 deletions

View File

@ -26,8 +26,6 @@
#include "AP_GPS_NOVA.h"
#include "AP_GPS_ERB.h"
#include "AP_GPS_GSOF.h"
#include "AP_GPS_MTK.h"
#include "AP_GPS_MTK19.h"
#include "AP_GPS_NMEA.h"
#include "AP_GPS_SBF.h"
#include "AP_GPS_SBP.h"
@ -72,7 +70,7 @@ const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57
// initialisation blobs to send to the GPS to try to get it into the
// right mode
const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY_230400 MTK_SET_BINARY SIRF_SET_BINARY;
const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY_230400 SIRF_SET_BINARY;
AP_GPS *AP_GPS::_singleton;
@ -81,7 +79,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @Param: _TYPE
// @DisplayName: 1st GPS type
// @Description: GPS type of 1st GPS
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:UAVCAN-MovingBaseline-Base,23:UAVCAN-MovingBaseline-Rover
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:UAVCAN-MovingBaseline-Base,23:UAVCAN-MovingBaseline-Rover
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("_TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
@ -90,7 +88,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @Param: _TYPE2
// @DisplayName: 2nd GPS type
// @Description: GPS type of 2nd GPS
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:UAVCAN-MovingBaseline-Base,23:UAVCAN-MovingBaseline-Rover
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:UAVCAN-MovingBaseline-Base,23:UAVCAN-MovingBaseline-Rover
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("_TYPE2", 1, AP_GPS, _type[1], 0),
@ -701,17 +699,6 @@ void AP_GPS::detect_instance(uint8_t instance)
new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance], role);
}
#ifndef HAL_BUILD_AP_PERIPH
#if !HAL_MINIMIZE_FEATURES
// we drop the MTK drivers when building a small build as they are so rarely used
// and are surprisingly large
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) &&
AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) {
new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]);
} else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) &&
AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) {
new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
}
#endif
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
new_gps = new AP_GPS_SBP2(*this, state[instance], _port[instance]);

View File

@ -67,8 +67,6 @@ class AP_GPS
friend class AP_GPS_MAV;
friend class AP_GPS_MSP;
friend class AP_GPS_ExternalAHRS;
friend class AP_GPS_MTK;
friend class AP_GPS_MTK19;
friend class AP_GPS_NMEA;
friend class AP_GPS_NOVA;
friend class AP_GPS_PX4;
@ -101,8 +99,8 @@ public:
GPS_TYPE_NONE = 0,
GPS_TYPE_AUTO = 1,
GPS_TYPE_UBLOX = 2,
GPS_TYPE_MTK = 3,
GPS_TYPE_MTK19 = 4,
// GPS_TYPE_MTK = 3, // driver removed
// GPS_TYPE_MTK19 = 4, // driver removed
GPS_TYPE_NMEA = 5,
GPS_TYPE_SIRF = 6,
GPS_TYPE_HIL = 7,
@ -618,8 +616,6 @@ private:
uint8_t current_baud;
bool auto_detected_baud;
struct UBLOX_detect_state ublox_detect_state;
struct MTK_detect_state mtk_detect_state;
struct MTK19_detect_state mtk19_detect_state;
struct SIRF_detect_state sirf_detect_state;
struct NMEA_detect_state nmea_detect_state;
struct SBP_detect_state sbp_detect_state;

View File

@ -1,218 +0,0 @@
/*
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/>.
*/
//
// 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"
//
#include "AP_GPS.h"
#include "AP_GPS_MTK.h"
// initialisation blobs to send to the GPS to try to get it into the
// right mode
const char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF;
AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
AP_GPS_Backend(_gps, _state, _port)
{
gps.send_blob_start(state.instance, _initialisation_blob, sizeof(_initialisation_blob));
}
/*
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));
}
// 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_MTK::read(void)
{
uint8_t data;
int16_t numc;
bool parsed = false;
numc = port->available();
for (int16_t i = 0; i < numc; i++) { // Process bytes received
// read the next byte
data = port->read();
restart:
switch(_step) {
// 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:
if(PREAMBLE1 == data)
_step++;
break;
case 1:
if (PREAMBLE2 == data) {
_step++;
break;
}
_step = 0;
goto restart;
case 2:
if (MESSAGE_CLASS == data) {
_step++;
_ck_b = _ck_a = data; // reset the checksum accumulators
} else {
_step = 0; // reset and wait for a message of the right class
goto restart;
}
break;
case 3:
if (MESSAGE_ID == data) {
_step++;
_ck_b += (_ck_a += data);
_payload_counter = 0;
} else {
_step = 0;
goto restart;
}
break;
// Receive message data
//
case 4:
_buffer[_payload_counter++] = data;
_ck_b += (_ck_a += data);
if (_payload_counter == sizeof(_buffer))
_step++;
break;
// Checksum and message processing
//
case 5:
_step++;
if (_ck_a != data) {
_step = 0;
}
break;
case 6:
_step = 0;
if (_ck_b != data) {
break;
}
// set fix type
if (_buffer.msg.fix_type == FIX_3D) {
state.status = AP_GPS::GPS_OK_FIX_3D;
}else if (_buffer.msg.fix_type == FIX_2D) {
state.status = AP_GPS::GPS_OK_FIX_2D;
}else{
state.status = AP_GPS::NO_FIX;
}
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;
state.ground_course = wrap_360(swap_int32(_buffer.msg.ground_course) * 1.0e-6f);
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);
}
// we don't change _last_gps_time as we don't know the
// full date
fill_3d_velocity();
parsed = true;
}
}
return parsed;
}
/*
detect a MTK GPS
*/
bool
AP_GPS_MTK::_detect(struct MTK_detect_state &state, uint8_t data)
{
switch (state.step) {
case 1:
if (PREAMBLE2 == data) {
state.step++;
break;
}
state.step = 0;
FALLTHROUGH;
case 0:
state.ck_b = state.ck_a = state.payload_counter = 0;
if(PREAMBLE1 == data)
state.step++;
break;
case 2:
if (MESSAGE_CLASS == data) {
state.step++;
state.ck_b = state.ck_a = data;
} else {
state.step = 0;
}
break;
case 3:
if (MESSAGE_ID == data) {
state.step++;
state.ck_b += (state.ck_a += data);
state.payload_counter = 0;
} else {
state.step = 0;
}
break;
case 4:
state.ck_b += (state.ck_a += data);
if (++state.payload_counter == sizeof(struct diyd_mtk_msg))
state.step++;
break;
case 5:
state.step++;
if (state.ck_a != data) {
state.step = 0;
}
break;
case 6:
state.step = 0;
if (state.ck_b == data) {
return true;
}
}
return false;
}

View File

@ -1,83 +0,0 @@
/*
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/>.
*/
//
// 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"
//
// Note - see AP_GPS_MTK16.h for firmware 1.6 and later.
//
#pragma once
#include "AP_GPS.h"
#include "GPS_Backend.h"
#include "AP_GPS_MTK_Common.h"
class AP_GPS_MTK : public AP_GPS_Backend {
public:
AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
bool read(void) override;
static bool _detect(struct MTK_detect_state &state, uint8_t data);
static void send_init_blob(uint8_t instance, AP_GPS &gps);
const char *name() const override { return "MTK"; }
private:
struct PACKED 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;
};
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
uint8_t _ck_a;
uint8_t _ck_b;
// State machine state
uint8_t _step;
uint8_t _payload_counter;
// Receive buffer
union PACKED {
DEFINE_BYTE_ARRAY_METHODS
diyd_mtk_msg msg;
} _buffer;
// Buffer parse & GPS state update
void _parse_gps();
static const char _initialisation_blob[];
};

View File

@ -1,234 +0,0 @@
/*
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/>.
*/
//
// 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 "DIYDrones Custom Binary Sentence Specification V1.6, v1.7, v1.8, v1.9"
//
// Note that this driver supports both the 1.6 and 1.9 protocol variants
//
#include "AP_GPS_MTK.h"
#include "AP_GPS_MTK19.h"
extern const AP_HAL::HAL& hal;
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)
{
AP_GPS_MTK::send_init_blob(_state.instance, _gps);
}
// 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;
numc = port->available();
for (int16_t i = 0; i < numc; i++) { // Process bytes received
// read the next byte
data = port->read();
restart:
switch(_step) {
// 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:
if (data == PREAMBLE1_V16) {
_mtk_revision = MTK_GPS_REVISION_V16;
_step++;
} else if (data == PREAMBLE1_V19) {
_mtk_revision = MTK_GPS_REVISION_V19;
_step++;
}
break;
case 1:
if (data == PREAMBLE2) {
_step++;
} else {
_step = 0;
goto restart;
}
break;
case 2:
if (sizeof(_buffer) == data) {
_step++;
_ck_b = _ck_a = data; // reset the checksum accumulators
_payload_counter = 0;
} else {
_step = 0; // reset and wait for a message of the right class
goto restart;
}
break;
// Receive message data
//
case 3:
_buffer[_payload_counter++] = data;
_ck_b += (_ck_a += data);
if (_payload_counter == sizeof(_buffer)) {
_step++;
}
break;
// Checksum and message processing
//
case 4:
_step++;
if (_ck_a != data) {
_step = 0;
goto restart;
}
break;
case 5:
_step = 0;
if (_ck_b != data) {
goto restart;
}
// parse fix
if (_buffer.msg.fix_type == FIX_3D || _buffer.msg.fix_type == FIX_3D_SBAS) {
state.status = AP_GPS::GPS_OK_FIX_3D;
}else if (_buffer.msg.fix_type == FIX_2D || _buffer.msg.fix_type == FIX_2D_SBAS) {
state.status = AP_GPS::GPS_OK_FIX_2D;
}else{
state.status = AP_GPS::NO_FIX;
}
if (_mtk_revision == MTK_GPS_REVISION_V16) {
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
} else {
state.location.lat = _buffer.msg.latitude;
state.location.lng = _buffer.msg.longitude;
}
state.location.alt = _buffer.msg.altitude;
state.ground_speed = _buffer.msg.ground_speed*0.01f;
state.ground_course = wrap_360(_buffer.msg.ground_course*0.01f);
state.num_sats = _buffer.msg.satellites;
state.hdop = _buffer.msg.hdop;
if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
if (_fix_counter == 0) {
uint32_t bcd_time_ms;
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
make_gps_time(_buffer.msg.utc_date, bcd_time_ms);
state.last_gps_time_ms = AP_HAL::millis();
}
// 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;
}
}
fill_3d_velocity();
parsed = true;
}
}
return parsed;
}
/*
detect a MTK16 or MTK19 GPS
*/
bool
AP_GPS_MTK19::_detect(struct MTK19_detect_state &state, uint8_t data)
{
restart:
switch (state.step) {
case 0:
state.ck_b = state.ck_a = state.payload_counter = 0;
if (data == PREAMBLE1_V16 || data == PREAMBLE1_V19) {
state.step++;
}
break;
case 1:
if (PREAMBLE2 == data) {
state.step++;
} else {
state.step = 0;
goto restart;
}
break;
case 2:
if (data == sizeof(struct diyd_mtk_msg)) {
state.step++;
state.ck_b = state.ck_a = data;
} else {
state.step = 0;
goto restart;
}
break;
case 3:
state.ck_b += (state.ck_a += data);
if (++state.payload_counter == sizeof(struct diyd_mtk_msg))
state.step++;
break;
case 4:
state.step++;
if (state.ck_a != data) {
state.step = 0;
goto restart;
}
break;
case 5:
state.step = 0;
if (state.ck_b != data) {
goto restart;
}
return true;
}
return false;
}

View File

@ -1,84 +0,0 @@
/*
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/>.
*/
//
// 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"
//
#pragma once
#include "AP_GPS.h"
#include "GPS_Backend.h"
#include "AP_GPS_MTK_Common.h"
#define MTK_GPS_REVISION_V16 16
#define MTK_GPS_REVISION_V19 19
class AP_GPS_MTK19 : public AP_GPS_Backend {
public:
AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
bool read(void) override;
static bool _detect(struct MTK19_detect_state &state, uint8_t data);
const char *name() const override { return "MTK19"; }
private:
struct PACKED 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_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,
PREAMBLE2 = 0xdd,
};
// Packet checksum accumulators
uint8_t _ck_a;
uint8_t _ck_b;
// State machine state
uint8_t _step;
uint8_t _payload_counter;
uint8_t _mtk_revision;
uint8_t _fix_counter;
// Receive buffer
union {
DEFINE_BYTE_ARRAY_METHODS
diyd_mtk_msg msg;
} _buffer;
};

View File

@ -1,40 +0,0 @@
/*
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/>.
*/
//
// DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega.
// Code by Michael Smith, Jordi Munoz and Jose Julio, Craig Elder, DIYDrones.com
//
// Common definitions for MediaTek GPS modules.
#pragma once
#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"
#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_OUTPUT_5HZ "$PMTK220,200*2C\r\n"
#define MTK_OUTPUT_10HZ "$PMTK220,100*2F\r\n"
#define MTK_BAUD_RATE_38400 "$PMTK251,38400*27\r\n"
#define MTK_NAVTHRES_OFF "$PMTK397,0*23\r\n" // Set Nav Threshold (the minimum speed the GPS must be moving to update the position) to 0 m/s
#define SBAS_ON "$PMTK313,1*2E\r\n"
#define SBAS_OFF "$PMTK313,0*2F\r\n"
#define WAAS_ON "$PMTK301,2*2E\r\n"
#define WAAS_OFF "$PMTK301,0*2C\r\n"

View File

@ -155,7 +155,6 @@ private:
/// in using these strings
//@{
static const char _SiRF_init_string[]; ///< init string for SiRF units
static const char _MTK_init_string[]; ///< init string for MediaTek units
static const char _ublox_init_string[]; ///< init string for ublox units
//@}

View File

@ -25,18 +25,6 @@
specific type that it handles.
*/
struct MTK19_detect_state {
uint8_t payload_counter;
uint8_t step;
uint8_t ck_a, ck_b;
};
struct MTK_detect_state {
uint8_t payload_counter;
uint8_t step;
uint8_t ck_a, ck_b;
};
struct NMEA_detect_state {
uint8_t step;
uint8_t ck;