AP_GPS: fixed MTK1.6 time handling

my MTK1.6 does not use hectoseconds, it uses milliseconds
This commit is contained in:
Andrew Tridgell 2015-03-13 10:29:36 +11:00
parent d9342ed854
commit 5da80f44b1

View File

@ -151,11 +151,13 @@ restart:
if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
if (_fix_counter == 0) {
uint32_t bcd_time_ms;
if (_mtk_revision == MTK_GPS_REVISION_V16) {
bcd_time_ms = _buffer.msg.utc_time*10;
} else {
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 = hal.scheduler->millis();
}