mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_GPS: GPVTG can give new velocity
This commit is contained in:
parent
4beb1748c5
commit
a7079b730a
@ -318,6 +318,7 @@ bool AP_GPS_NMEA::_term_complete()
|
||||
_last_GPVTG_ms = now;
|
||||
state.ground_speed = _new_speed*0.01f;
|
||||
state.ground_course_cd = wrap_360_cd(_new_course);
|
||||
fill_3d_velocity();
|
||||
// VTG has no fix indicator, can't change fix status
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user