GPS: change back to 4Hz for MTK GPS

this will hopefully fix the NO_GPS problems that have been regularly
happening in recent months. I will watch the logs carefully to see if
the problem recurs
This commit is contained in:
Andrew Tridgell 2012-02-13 22:50:20 +11:00
parent e70e1814ac
commit 4ec3857476
2 changed files with 4 additions and 4 deletions

View File

@ -28,8 +28,8 @@ AP_GPS_MTK::init(void)
// XXX should assume binary, let GPS_AUTO handle dynamic config?
_port->print(MTK_SET_BINARY);
// set 10Hz update rate
_port->print(MTK_OUTPUT_10HZ);
// set 4Hz update rate
_port->print(MTK_OUTPUT_4HZ);
// set initial epoch code
_epoch = TIME_OF_DAY;

View File

@ -34,8 +34,8 @@ AP_GPS_MTK16::init(void)
// XXX should assume binary, let GPS_AUTO handle dynamic config?
_port->print(MTK_SET_BINARY);
// set 10Hz update rate
_port->print(MTK_OUTPUT_10HZ);
// set 4Hz update rate
_port->print(MTK_OUTPUT_4HZ);
// set initial epoch code
_epoch = TIME_OF_DAY;