mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: add get_calibration_state in dummy driver
This commit is contained in:
parent
8b38cc671a
commit
d7357a3330
@ -893,6 +893,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND };
|
|||||||
void AP_Airspeed::update() {};
|
void AP_Airspeed::update() {};
|
||||||
bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) { return false; }
|
bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) { return false; }
|
||||||
void AP_Airspeed::calibrate(bool in_startup) {}
|
void AP_Airspeed::calibrate(bool in_startup) {}
|
||||||
|
AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const { return CalibrationState::NOT_STARTED; }
|
||||||
bool AP_Airspeed::use(uint8_t i) const { return false; }
|
bool AP_Airspeed::use(uint8_t i) const { return false; }
|
||||||
bool AP_Airspeed::enabled(uint8_t i) const { return false; }
|
bool AP_Airspeed::enabled(uint8_t i) const { return false; }
|
||||||
bool AP_Airspeed::healthy(uint8_t i) const { return false; }
|
bool AP_Airspeed::healthy(uint8_t i) const { return false; }
|
||||||
|
Loading…
Reference in New Issue
Block a user