From 14aea255e6dc54b19909b33132505370d4d9a369 Mon Sep 17 00:00:00 2001 From: Hayden Donald Date: Thu, 16 Nov 2023 11:40:05 +1100 Subject: [PATCH] AP_Scripting: Add calibrating method Add the calibrating method to lua so we can see if the device is currently calibrating --- libraries/AP_Scripting/docs/docs.lua | 4 ++++ libraries/AP_Scripting/generator/description/bindings.desc | 1 + 2 files changed, 5 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 5a6589610b..ebbe49d515 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -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 = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index c608870c87..951f175757 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -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