mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
AP_GPS: fixed time handling with NMEA driver
This commit is contained in:
parent
a852e48f37
commit
3b1b7ea029
@ -280,6 +280,7 @@ bool AP_GPS_NMEA::_term_complete()
|
|||||||
state.ground_speed = _new_speed*0.01f;
|
state.ground_speed = _new_speed*0.01f;
|
||||||
state.ground_course_cd = _new_course;
|
state.ground_course_cd = _new_course;
|
||||||
make_gps_time(_new_date, _new_time * 10);
|
make_gps_time(_new_date, _new_time * 10);
|
||||||
|
state.last_gps_time_ms = hal.scheduler->millis();
|
||||||
// To-Do: add support for proper reporting of 2D and 3D fix
|
// To-Do: add support for proper reporting of 2D and 3D fix
|
||||||
state.status = AP_GPS::GPS_OK_FIX_3D;
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
||||||
fill_3d_velocity();
|
fill_3d_velocity();
|
||||||
|
Loading…
Reference in New Issue
Block a user