mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: added bindings for VTOL motor loss
this allows a script to take an action on loss of a VTOL motor
This commit is contained in:
parent
4957173f45
commit
a564af680b
|
@ -1327,6 +1327,13 @@ function MotorsMatrix:add_motor_raw(motor_num, roll_factor, pitch_factor, yaw_fa
|
||||||
---@return boolean
|
---@return boolean
|
||||||
function MotorsMatrix:init(expected_num_motors) end
|
function MotorsMatrix:init(expected_num_motors) end
|
||||||
|
|
||||||
|
-- desc get index (starting at 0) of lost motor
|
||||||
|
---@return integer
|
||||||
|
function MotorsMatrix:get_lost_motor() end
|
||||||
|
|
||||||
|
-- desc return true if we are in thrust boost due to possible lost motor
|
||||||
|
---@return boolean
|
||||||
|
function MotorsMatrix:get_thrust_boost() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@class quadplane
|
---@class quadplane
|
||||||
|
|
|
@ -0,0 +1,27 @@
|
||||||
|
--[[
|
||||||
|
display motor lost number from MotorsMatrix for multirotors
|
||||||
|
--]]
|
||||||
|
|
||||||
|
local last_motor_lost = -1
|
||||||
|
|
||||||
|
function update()
|
||||||
|
local lost_index
|
||||||
|
if not MotorsMatrix:get_thrust_boost() then
|
||||||
|
-- when get_thrust_boost is false then we have not lost a motor
|
||||||
|
lost_index = -1
|
||||||
|
else
|
||||||
|
-- otherwise get the lost motor number
|
||||||
|
lost_index = MotorsMatrix:get_lost_motor()
|
||||||
|
end
|
||||||
|
if lost_index ~= last_motor_lost then
|
||||||
|
if lost_index == -1 then
|
||||||
|
gcs:send_text(0, string.format("Motors: recovered"))
|
||||||
|
else
|
||||||
|
gcs:send_text(0, string.format("Motors: lost motor %d", lost_index+1))
|
||||||
|
end
|
||||||
|
last_motor_lost = lost_index
|
||||||
|
end
|
||||||
|
return update, 100
|
||||||
|
end
|
||||||
|
|
||||||
|
return update, 100
|
|
@ -444,6 +444,8 @@ singleton AP_MotorsMatrix rename MotorsMatrix
|
||||||
singleton AP_MotorsMatrix method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
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 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 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
|
include AP_Frsky_Telem/AP_Frsky_SPort.h
|
||||||
singleton AP_Frsky_SPort rename frsky_sport
|
singleton AP_Frsky_SPort rename frsky_sport
|
||||||
|
|
Loading…
Reference in New Issue