AP_GPS: fixed vertical velocity in Replay

fixed NavEKF use of velocity velocity
This commit is contained in:
Andrew Tridgell 2014-12-09 18:57:17 +11:00
parent 4a91546ced
commit 3354cb37d0
1 changed files with 1 additions and 0 deletions

View File

@ -411,6 +411,7 @@ AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
istate.location = _location;
istate.location.options = 0;
istate.velocity = _velocity;
istate.have_vertical_velocity = true;
istate.ground_speed = pythagorous2(istate.velocity.x, istate.velocity.y);
istate.ground_course_cd = degrees(atan2f(istate.velocity.y, istate.velocity.x)) * 100UL;
istate.hdop = hdop;