diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 817940309f..320724c211 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -28,8 +28,14 @@ AP_GPS_MTK::init(enum GPS_Engine_Setting nav_setting) // XXX should assume binary, let GPS_AUTO handle dynamic config? _port->print(MTK_SET_BINARY); - // set 4Hz update rate - _port->print(MTK_OUTPUT_4HZ); + // set 5Hz update rate + _port->print(MTK_OUTPUT_5HZ); + + // set SBAS on + _port->print(SBAS_ON); + + // set WAAS on + _port->print(WAAS_ON); // set initial epoch code _epoch = TIME_OF_DAY; @@ -129,7 +135,7 @@ restart: break; } - fix = (_buffer.msg.fix_type == FIX_3D); + fix = ((_buffer.msg.fix_type == FIX_3D) || (_buffer.msg.fix_type == FIX_3D_SBAS); latitude = _swapl(&_buffer.msg.latitude) * 10; longitude = _swapl(&_buffer.msg.longitude) * 10; altitude = _swapl(&_buffer.msg.altitude); diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index 1f13fb4e83..a221386f87 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -40,7 +40,9 @@ private: enum diyd_mtk_fix_type { FIX_NONE = 1, FIX_2D = 2, - FIX_3D = 3 + FIX_3D = 3, + FIX_3D_SBAS = 6, + FIX_3D_SBAS =7 }; enum diyd_mtk_protocol_bytes { diff --git a/libraries/AP_GPS/AP_GPS_MTK16.cpp b/libraries/AP_GPS/AP_GPS_MTK16.cpp index cdd637e390..1985250d9b 100644 --- a/libraries/AP_GPS/AP_GPS_MTK16.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK16.cpp @@ -34,9 +34,15 @@ AP_GPS_MTK16::init(enum GPS_Engine_Setting nav_setting) // XXX should assume binary, let GPS_AUTO handle dynamic config? _port->print(MTK_SET_BINARY); - // set 4Hz update rate - _port->print(MTK_OUTPUT_4HZ); + // set 5Hz update rate + _port->print(MTK_OUTPUT_5HZ); + // set SBAS on + _port->print(SBAS_ON); + + // set WAAS on + _port->print(WAAS_ON); + // set initial epoch code _epoch = TIME_OF_DAY; _time_offset = 0; @@ -125,7 +131,7 @@ restart: break; } - fix = _buffer.msg.fix_type == FIX_3D; + fix = ((_buffer.msg.fix_type == FIX_3D) || (_buffer.msg.fix_type == FIX_3D_SBAS); latitude = _buffer.msg.latitude * 10; // XXX doc says *10e7 but device says otherwise longitude = _buffer.msg.longitude * 10; // XXX doc says *10e7 but device says otherwise altitude = _buffer.msg.altitude; diff --git a/libraries/AP_GPS/AP_GPS_MTK_Common.h b/libraries/AP_GPS/AP_GPS_MTK_Common.h index 68ef91dd3e..06338600a1 100644 --- a/libraries/AP_GPS/AP_GPS_MTK_Common.h +++ b/libraries/AP_GPS/AP_GPS_MTK_Common.h @@ -19,7 +19,7 @@ #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_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"