Skip to content

Commit

Permalink
AP_Scripting: Lua bindings for safety checks ESC, MotorsMatrix
Browse files Browse the repository at this point in the history
This commit introduces Lua bindings for the following methods:

- ESC- `get_last_telem_data_ms`
- MotorMatrix `get_lost_motor`
- MotorMatrix `get_thrust_boost`

Note:
- For get_last_telem_data_ms - CPN reset is reported. But ESC disconnected with CPN is not reported. This needs to be looked into

SW-61
  • Loading branch information
loki077 committed Apr 8, 2024
1 parent 02b627a commit 77c610d
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 34 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@

local SCRIPT_NAME = 'CX_BIT'
local CX_SANITY_SCRIPT_VERSION = 1.0 -- Script Version
local CX_PILOT_MIN_FW_VERSION = 5.0 -- Minimum Firmware Version Supported e.g CxPilot 5.0.0 should be mentioned as 5.0
local CX_PILOT_MIN_FW_VERSION = 4.4 -- Minimum Firmware Version Supported e.g Volanti 4.4.0 should be mentioned as 4.0


-------- MAVLINK/AUTOPILOT 'CONSTANTS' --------
Expand All @@ -31,11 +31,6 @@ local MSG_NORMAL = 1 -- 1 for normal status messages
local MSG_DEBUG = 2 -- 2 for additional debug messages
local VERBOSE_MODE = 2 -- 0 to suppress all GCS messages, 1 for normal status messages, 2 for additional debug messages

local M1 = 0
local M2 = 1
local M3 = 2
local M4 = 3
local M5 = 4
local WARNING_MSG_TIMEOUT = 15

local UNKNOWN = 0
Expand All @@ -47,11 +42,9 @@ local HIRTH_EFI_TYPE = 8

local aircraft_type = UNKNOWN

local pre_arm_init = false

local servo_previous_telem_data_ms = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}
local servo_telem_in_error_status = {false, false, false, false, false, false, false}
local motor_in_error_status = {false, false, false, false, false, false, false}
local last_motor_lost = -1

local number_of_esc = 5
Expand Down Expand Up @@ -111,7 +104,7 @@ local function pre_arm_check_init()
local version = cx_version:match("(%d+%.%d+)")

-- check if firmware has CxPilot or Volanti or Ottano
if cx_version:find("CxPilot") or cx_version:find("Volanti") or cx_version:find("Ottano") then
if cx_version:find("CxPilot") or cx_version:find("ArduPlane") or cx_version:find("Volanti") or cx_version:find("Ottano") then
version = tonumber(version)
if CX_PILOT_MIN_FW_VERSION > version then
arming:set_aux_auth_failed(auth_id, string.format('%s Requires: %.1f. Found Version: %s', SCRIPT_NAME, CX_PILOT_MIN_FW_VERSION, version))
Expand Down Expand Up @@ -153,7 +146,6 @@ local function pre_arm_check_loop()
if esc_last_telem_data_ms ~= nil and esc_last_telem_data_ms ~= 0 then
servo_previous_telem_data_ms[i] = esc_last_telem_data_ms
end
return -1
else
if servo_telem_in_error_status[i] == true then
gcs_msg(MSG_NORMAL, MAV_SEVERITY_INFO, "ESC " .. i .. " Telemetry Recovered")
Expand All @@ -176,7 +168,12 @@ local function pre_arm_check_loop()

-- check servo

arming:set_aux_auth_passed(auth_id)
for i, status in ipairs(servo_telem_in_error_status) do
if status == false then
arming:set_aux_auth_passed(auth_id)
end
end

return 0
end

Expand All @@ -190,20 +187,16 @@ local function vtol_failure_check()
end
end

local last_fail_msg_time = 0
local telem_failure = false

local function during_arm_check_loop()
--check ESC Telemetry is done in pre_arm_check_loop
vtol_failure_check()
if arming:is_armed() then
--check ESC Telemetry is done in pre_arm_check_loop
vtol_failure_check()
end
end

local function update()
pre_arm_check_loop()

if arming:is_armed() then
during_arm_check_loop()
end
during_arm_check_loop()
end

-- wrapper around update(). This calls update() and if update faults
Expand All @@ -225,24 +218,23 @@ local function script_exit()
gcs_msg(MSG_NORMAL, MAV_SEVERITY_CRITICAL, "LUA SCRIPT EXIT ... Need Reboot to Reinitialize")
end

local function test_print_esc_telem()
local val = tostring(esc_telem:get_last_telem_data_ms(0):toint())
gcs:send_text(0, "ESC 0 Telemetry: " .. val)
val = tostring(esc_telem:get_last_telem_data_ms(1):toint())
gcs:send_text(0, "ESC 1 Telemetry: " .. val)
val = tostring(esc_telem:get_last_telem_data_ms(2):toint())
gcs:send_text(0, "ESC 2 Telemetry: " .. val)
val = tostring(esc_telem:get_last_telem_data_ms(3):toint())
gcs:send_text(0, "ESC 3 Telemetry: " .. val)
return test, 500
end
-- local function test_print_esc_telem()
-- local val = tostring(esc_telem:get_last_telem_data_ms(0):toint())
-- gcs:send_text(0, "ESC 0 Telemetry: " .. val)
-- val = tostring(esc_telem:get_last_telem_data_ms(1):toint())
-- gcs:send_text(0, "ESC 1 Telemetry: " .. val)
-- val = tostring(esc_telem:get_last_telem_data_ms(2):toint())
-- gcs:send_text(0, "ESC 2 Telemetry: " .. val)
-- val = tostring(esc_telem:get_last_telem_data_ms(3):toint())
-- gcs:send_text(0, "ESC 3 Telemetry: " .. val)
-- return test, 500
-- end
-- return test_print_esc_telem()

-- ******************* Main *******************
gcs_msg(MSG_NORMAL, MAV_SEVERITY_INFO, "Script Version " .. CX_SANITY_SCRIPT_VERSION .. " Running")
if pre_arm_check_init() == 0 then
return protected_wrapper()
end

-- return test_print_esc_telem()

script_exit()
script_exit()
3 changes: 3 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -304,6 +304,7 @@ singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS f
singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null
singleton AP_ESC_Telem method get_last_telem_data_ms uint32_t uint8_t 0 NUM_SERVO_CHANNELS

include AP_Param/AP_Param.h
singleton AP_Param alias param
Expand Down Expand Up @@ -383,6 +384,8 @@ singleton AP_MotorsMatrix alias MotorsMatrix
singleton AP_MotorsMatrix method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
singleton AP_MotorsMatrix method add_motor_raw void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float'skip_check float'skip_check float'skip_check uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
singleton AP_MotorsMatrix method set_throttle_factor boolean int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float 0 FLT_MAX
singleton AP_MotorsMatrix method get_lost_motor uint8_t
singleton AP_MotorsMatrix method get_thrust_boost boolean

include AP_Frsky_Telem/AP_Frsky_SPort.h
singleton AP_Frsky_SPort alias frsky_sport
Expand Down

0 comments on commit 77c610d

Please sign in to comment.