mirror of https://github.com/ArduPilot/ardupilot
add checks
This commit is contained in:
parent
dd4ad8a993
commit
d36b967e8d
|
@ -65,10 +65,10 @@ singleton AP_AHRS method get_quaternion boolean Quaternion'Null
|
|||
include AP_Airspeed/AP_Airspeed.h
|
||||
singleton AP_Airspeed depends AP_AIRSPEED_ENABLED
|
||||
singleton AP_Airspeed rename airspeed
|
||||
singleton AP_Airspeed method enabled boolean uint8_t'skip_check
|
||||
singleton AP_Airspeed method healthy boolean uint8_t'skip_check
|
||||
singleton AP_Airspeed method get_airspeed float uint8_t'skip_check
|
||||
singleton AP_Airspeed method get_raw_airspeed float uint8_t'skip_check
|
||||
singleton AP_Airspeed method enabled boolean uint8_t 0 (AIRSPEED_MAX_SENSORS-1)
|
||||
singleton AP_Airspeed method healthy boolean uint8_t 0 (AIRSPEED_MAX_SENSORS-1)
|
||||
singleton AP_Airspeed method get_airspeed float uint8_t 0 (AIRSPEED_MAX_SENSORS-1)
|
||||
singleton AP_Airspeed method get_raw_airspeed float uint8_t 0 (AIRSPEED_MAX_SENSORS-1)
|
||||
|
||||
include AP_Arming/AP_Arming.h
|
||||
|
||||
|
|
Loading…
Reference in New Issue