SITL: run the HIL barometer at 80Hz to match APM2

This commit is contained in:
Andrew Tridgell 2012-07-05 16:27:13 +10:00
parent 735c88e9b3
commit 5f38669666

View File

@ -25,6 +25,13 @@ void sitl_update_barometer(float altitude)
{ {
extern AP_Baro_BMP085_HIL barometer; extern AP_Baro_BMP085_HIL barometer;
double Temp, Press, y; double Temp, Press, y;
static uint32_t last_update;
// 80Hz, to match the real APM2 barometer
if (millis() - last_update < 12) {
return;
}
last_update = millis();
Temp = 312; Temp = 312;