mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add scripting backend
AP_BattMonitor_Scripting: whitespace consistency
This commit is contained in:
parent
fd855781d8
commit
1ffda7ef3c
|
@ -817,6 +817,150 @@ function Vector3f_ud:normalize() end
|
|||
---@return number
|
||||
function Vector3f_ud:length() end
|
||||
|
||||
|
||||
-- desc
|
||||
---@class BattMonitorScript_State_ud
|
||||
local BattMonitorScript_State_ud = {}
|
||||
|
||||
---@return BattMonitorScript_State_ud
|
||||
function BattMonitorScript_State() end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:resting_voltage() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:resting_voltage(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:resistance() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:resistance(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function BattMonitorScript_State_ud:mavlink_faults() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud
|
||||
function BattMonitorScript_State_ud:mavlink_faults(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
---| '0' # None
|
||||
---| '1' # Low
|
||||
---| '2' # Critical
|
||||
function BattMonitorScript_State_ud:failsafe() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
---| '0' # None
|
||||
---| '1' # Low
|
||||
---| '2' # Critical
|
||||
function BattMonitorScript_State_ud:failsafe(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function BattMonitorScript_State_ud:time_remaining() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud
|
||||
function BattMonitorScript_State_ud:time_remaining(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function BattMonitorScript_State_ud:cycle_count() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function BattMonitorScript_State_ud:cycle_count(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function BattMonitorScript_State_ud:capacity_remaining_pct() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function BattMonitorScript_State_ud:capacity_remaining_pct(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:temperature() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:temperature(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:consumed_wh() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:consumed_wh(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:consumed_mah() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:consumed_mah(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:current_amps() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:current_amps(value) end
|
||||
|
||||
-- get array field
|
||||
---@param index integer
|
||||
---@return integer
|
||||
function BattMonitorScript_State_ud:cell_voltages(index) end
|
||||
|
||||
-- set array field
|
||||
---@param index integer
|
||||
---@param value integer
|
||||
function BattMonitorScript_State_ud:cell_voltages(index, value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function BattMonitorScript_State_ud:cell_count() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function BattMonitorScript_State_ud:cell_count(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function BattMonitorScript_State_ud:voltage() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function BattMonitorScript_State_ud:voltage(value) end
|
||||
|
||||
-- get field
|
||||
---@return boolean
|
||||
function BattMonitorScript_State_ud:healthy() end
|
||||
|
||||
-- set field
|
||||
---@param value boolean
|
||||
function BattMonitorScript_State_ud:healthy(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function BattMonitorScript_State_ud:last_update_us() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud
|
||||
function BattMonitorScript_State_ud:last_update_us(value) end
|
||||
|
||||
-- Computes angle between this vector and vector v2
|
||||
---@param v2 Vector3f_ud
|
||||
---@return number
|
||||
|
@ -1181,6 +1325,15 @@ function RC_Channel_ud:norm_input() end
|
|||
---@return number
|
||||
function RC_Channel_ud:norm_input_dz() end
|
||||
|
||||
-- desc
|
||||
---@class AP_BattMonitor_Backend_ud
|
||||
local AP_BattMonitor_Backend_ud = {}
|
||||
|
||||
-- desc
|
||||
---@param battmon_state BattMonitorScript_State_ud
|
||||
---@return boolean
|
||||
function AP_BattMonitor_Backend_ud:handle_scripting(battmon_state) end
|
||||
|
||||
-- desc
|
||||
---@class winch
|
||||
winch = {}
|
||||
|
@ -2867,6 +3020,11 @@ function gps:num_sensors() end
|
|||
---@class battery
|
||||
battery = {}
|
||||
|
||||
-- desc
|
||||
---@param index integer
|
||||
---@return AP_BattMonitor_Backend_ud
|
||||
function battery:get_backend(index) end
|
||||
|
||||
-- desc
|
||||
---@param instance integer
|
||||
---@param percentage number
|
||||
|
|
|
@ -76,6 +76,19 @@ singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string
|
|||
|
||||
include AP_BattMonitor/AP_BattMonitor.h
|
||||
|
||||
include AP_BattMonitor/AP_BattMonitor_Scripting.h
|
||||
userdata BattMonitorScript_State depends AP_BATTERY_SCRIPTING_ENABLED == 1
|
||||
userdata BattMonitorScript_State field healthy boolean write
|
||||
userdata BattMonitorScript_State field voltage float'skip_check write
|
||||
userdata BattMonitorScript_State field cell_count uint8_t'skip_check write
|
||||
userdata BattMonitorScript_State field capacity_remaining_pct uint8_t'skip_check write
|
||||
userdata BattMonitorScript_State field cell_voltages'array int(ARRAY_SIZE(ud->cell_voltages)) uint16_t'skip_check write
|
||||
userdata BattMonitorScript_State field cycle_count uint16_t'skip_check write
|
||||
userdata BattMonitorScript_State field current_amps float'skip_check write
|
||||
userdata BattMonitorScript_State field consumed_mah float'skip_check write
|
||||
userdata BattMonitorScript_State field consumed_wh float'skip_check write
|
||||
userdata BattMonitorScript_State field temperature float'skip_check write
|
||||
|
||||
singleton AP_BattMonitor rename battery
|
||||
singleton AP_BattMonitor depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY))
|
||||
singleton AP_BattMonitor method num_instances uint8_t
|
||||
|
@ -93,6 +106,7 @@ singleton AP_BattMonitor method get_temperature boolean float'Null uint8_t 0 ud-
|
|||
singleton AP_BattMonitor method get_cycle_count boolean uint8_t 0 ud->num_instances() uint16_t'Null
|
||||
singleton AP_BattMonitor method reset_remaining boolean uint8_t 0 ud->num_instances() float 0 100
|
||||
singleton AP_BattMonitor method get_cell_voltage boolean uint8_t'skip_check uint8_t'skip_check float'Null
|
||||
singleton AP_BattMonitor method handle_scripting boolean uint8_t'skip_check BattMonitorScript_State
|
||||
|
||||
include AP_GPS/AP_GPS.h
|
||||
|
||||
|
|
Loading…
Reference in New Issue