AP_GPS: fixed HIL GPS driver to make have vertical velocity sticky

This commit is contained in:
Andrew Tridgell 2015-06-16 15:48:10 +10:00
parent 47834759e5
commit f77ffd30f6

View File

@ -428,12 +428,11 @@ 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;
istate.num_sats = _num_sats;
istate.have_vertical_velocity = _have_vertical_velocity;
istate.have_vertical_velocity |= _have_vertical_velocity;
istate.last_gps_time_ms = tnow;
uint64_t gps_time_ms = time_epoch_ms - (17000ULL*86400ULL + 52*10*7000ULL*86400ULL - 15000ULL);
istate.time_week = gps_time_ms / (86400*7*(uint64_t)1000);