mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
SITL: run the HIL barometer at 80Hz to match APM2
This commit is contained in:
parent
735c88e9b3
commit
5f38669666
@ -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;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user