Browse Source

GPS: Corrections to Media Tek GPS Driver. Change to 5Hz and SBAS

master
Craig Elder 13 years ago committed by Andrew Tridgell
parent
commit
2493ffaad1
  1. 12
      libraries/AP_GPS/AP_GPS_MTK.cpp
  2. 4
      libraries/AP_GPS/AP_GPS_MTK.h
  3. 14
      libraries/AP_GPS/AP_GPS_MTK16.cpp
  4. 2
      libraries/AP_GPS/AP_GPS_MTK_Common.h

12
libraries/AP_GPS/AP_GPS_MTK.cpp

@ -28,8 +28,14 @@ AP_GPS_MTK::init(enum GPS_Engine_Setting nav_setting) @@ -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: @@ -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);

4
libraries/AP_GPS/AP_GPS_MTK.h

@ -40,7 +40,9 @@ private: @@ -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 {

14
libraries/AP_GPS/AP_GPS_MTK16.cpp

@ -34,9 +34,15 @@ AP_GPS_MTK16::init(enum GPS_Engine_Setting nav_setting) @@ -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: @@ -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;

2
libraries/AP_GPS/AP_GPS_MTK_Common.h

@ -19,7 +19,7 @@ @@ -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"

Loading…
Cancel
Save