mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: implement SIM_GPSDRIFTALT
This commit is contained in:
parent
63c792bc1c
commit
869fb23062
|
@ -759,6 +759,12 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
|
||||||
d.latitude = latitude + glitch_offsets.x;
|
d.latitude = latitude + glitch_offsets.x;
|
||||||
d.longitude = longitude + glitch_offsets.y;
|
d.longitude = longitude + glitch_offsets.y;
|
||||||
d.altitude = altitude + glitch_offsets.z;
|
d.altitude = altitude + glitch_offsets.z;
|
||||||
|
|
||||||
|
if (_sitl->gps_drift_alt > 0) {
|
||||||
|
// slow altitude drift
|
||||||
|
d.altitude += _sitl->gps_drift_alt*sinf(hal.scheduler->millis()*0.001*0.02);
|
||||||
|
}
|
||||||
|
|
||||||
d.speedN = speedN;
|
d.speedN = speedN;
|
||||||
d.speedE = speedE;
|
d.speedE = speedE;
|
||||||
d.speedD = speedD;
|
d.speedD = speedD;
|
||||||
|
|
Loading…
Reference in New Issue