mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: added setHIL() method
useful for log playback
This commit is contained in:
parent
e11ada7bf0
commit
ad4db4de6c
|
@ -214,3 +214,11 @@ void AP_Airspeed::read(void)
|
|||
_airspeed = 0.7f * _airspeed + 0.3f * _raw_airspeed;
|
||||
_last_update_ms = hal.scheduler->millis();
|
||||
}
|
||||
|
||||
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();
|
||||
}
|
||||
|
|
|
@ -134,6 +134,8 @@ public:
|
|||
// return time in ms of last update
|
||||
uint32_t last_update_ms(void) const { return _last_update_ms; }
|
||||
|
||||
void setHIL(float airspeed, float diff_pressure, float temperature);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE =0,
|
||||
|
|
Loading…
Reference in New Issue