mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: added last_update_ms() interface
This commit is contained in:
parent
e7cf07dfb7
commit
03cc777991
|
@ -212,4 +212,5 @@ void AP_Airspeed::read(void)
|
|||
_last_pressure = airspeed_pressure;
|
||||
_raw_airspeed = sqrtf(airspeed_pressure * _ratio);
|
||||
_airspeed = 0.7f * _airspeed + 0.3f * _raw_airspeed;
|
||||
_last_update_ms = hal.scheduler->millis();
|
||||
}
|
||||
|
|
|
@ -131,6 +131,9 @@ public:
|
|||
// return health status of sensor
|
||||
bool healthy(void) const { return _healthy; }
|
||||
|
||||
// return time in ms of last update
|
||||
uint32_t last_update_ms(void) const { return _last_update_ms; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE =0,
|
||||
|
@ -150,6 +153,7 @@ private:
|
|||
float _last_pressure;
|
||||
float _EAS2TAS;
|
||||
bool _healthy;
|
||||
uint32_t _last_update_ms;
|
||||
|
||||
Airspeed_Calibration _calibration;
|
||||
float _last_saved_ratio;
|
||||
|
|
Loading…
Reference in New Issue