mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
SITL: zero wind for first 15s
this allows for airspeed calibration on startup
This commit is contained in:
parent
2e9e3ce5a6
commit
dd7c815c5f
@ -214,6 +214,11 @@ static void sitl_simulator_output(void)
|
||||
control.direction = direction * 100;
|
||||
control.turbulance = sitl.wind_turbulance * 100;
|
||||
|
||||
// zero the wind for the first 15s to allow pitot calibration
|
||||
if (millis() < 15000) {
|
||||
control.speed = 0;
|
||||
}
|
||||
|
||||
sendto(sitl_fd, (void*)&control, sizeof(control), MSG_DONTWAIT, (const sockaddr *)&rcout_addr, sizeof(rcout_addr));
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user