AP_Airspeed: fixed airspeed in Replay
This commit is contained in:
parent
fce20b24c2
commit
ef0eca4835
@ -240,5 +240,8 @@ void AP_Airspeed::setHIL(float airspeed, float diff_pressure, float temperature)
|
||||
_raw_airspeed = airspeed;
|
||||
_airspeed = airspeed;
|
||||
_last_pressure = diff_pressure;
|
||||
_last_update_ms = hal.scheduler->millis();
|
||||
_last_update_ms = hal.scheduler->millis();
|
||||
_hil_pressure = diff_pressure;
|
||||
_hil_set = true;
|
||||
_healthy = true;
|
||||
}
|
||||
|
@ -138,7 +138,7 @@ public:
|
||||
// return health status of sensor
|
||||
bool healthy(void) const { return _healthy; }
|
||||
|
||||
void setHIL(float pressure) { _hil_set=true; _hil_pressure=pressure; };
|
||||
void setHIL(float pressure) { _healthy=_hil_set=true; _hil_pressure=pressure; };
|
||||
|
||||
// return time in ms of last update
|
||||
uint32_t last_update_ms(void) const { return _last_update_ms; }
|
||||
|
Loading…
Reference in New Issue
Block a user