mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Add calibrating method
Add the calibrating method to lua so we can see if the device is currently calibrating
This commit is contained in:
parent
85a8b6c414
commit
14aea255e6
|
@ -1505,6 +1505,10 @@ function ins:get_gyro_health(instance) end
|
|||
---@return boolean
|
||||
function ins:get_accel_health(instance) end
|
||||
|
||||
-- Get if the INS is currently calibrating
|
||||
---@return boolean
|
||||
function ins:calibrating() end
|
||||
|
||||
-- desc
|
||||
---@class Motors_dynamic
|
||||
Motors_dynamic = {}
|
||||
|
|
|
@ -633,6 +633,7 @@ singleton AP_InertialSensor rename ins
|
|||
singleton AP_InertialSensor method get_temperature float uint8_t 0 INS_MAX_INSTANCES
|
||||
singleton AP_InertialSensor method get_gyro_health boolean uint8_t'skip_check
|
||||
singleton AP_InertialSensor method get_accel_health boolean uint8_t'skip_check
|
||||
singleton AP_InertialSensor method calibrating boolean
|
||||
|
||||
singleton CAN manual get_device lua_get_CAN_device 1
|
||||
singleton CAN manual get_device2 lua_get_CAN_device2 1
|
||||
|
|
Loading…
Reference in New Issue