mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add bindings for E-stop, Interlock and Safety state
This commit is contained in:
parent
ffcdcd88b2
commit
c5c7863829
|
@ -1037,6 +1037,12 @@ function mount:get_attitude_euler(instance) end
|
|||
---@class motors
|
||||
motors = {}
|
||||
|
||||
-- Get motors interlock state, the state of motors controlled by AP_Motors, Copter and Quadplane VTOL motors. Not plane forward flight motors.
|
||||
---@return boolean
|
||||
---| true # motors active
|
||||
---| false # motors inactive
|
||||
function motors:get_interlock() end
|
||||
|
||||
-- desc
|
||||
---@param param1 string
|
||||
function motors:set_frame_string(param1) end
|
||||
|
@ -1518,6 +1524,18 @@ function rc:get_pwm(chan_num) end
|
|||
---@class SRV_Channels
|
||||
SRV_Channels = {}
|
||||
|
||||
-- Get emergency stop state if active no motors of any kind will be active
|
||||
---@return boolean
|
||||
---| true # E-Stop active
|
||||
---| false # E-Stop inactive
|
||||
function SRV_Channels:get_emergency_stop() end
|
||||
|
||||
-- Get safety state
|
||||
---@return boolean
|
||||
---| true # Disarmed outputs inactive
|
||||
---| false # Armed outputs live
|
||||
function SRV_Channels:get_safety_state() end
|
||||
|
||||
-- desc
|
||||
---@param function_num integer
|
||||
---@param range integer
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
-- This Script is a example of the safety states avalalbe to lua
|
||||
|
||||
local last_armed
|
||||
local last_motors_armed
|
||||
local last_E_stop
|
||||
local last_safe
|
||||
function update()
|
||||
|
||||
local armed = arming:is_armed()
|
||||
if armed ~= last_armed then
|
||||
gcs:send_text(0, 'Vehicle armed: ' .. tostring(armed))
|
||||
end
|
||||
last_armed = armed
|
||||
|
||||
local motors_armed = motors:get_interlock()
|
||||
if motors_armed ~= last_motors_armed then
|
||||
gcs:send_text(0, 'Motors armed: ' .. tostring(motors_armed))
|
||||
end
|
||||
last_motors_armed = motors_armed
|
||||
|
||||
local E_stop = SRV_Channels:get_emergency_stop()
|
||||
if E_stop ~= last_E_stop then
|
||||
gcs:send_text(0, 'E-Stop active: ' .. tostring(E_stop))
|
||||
end
|
||||
last_E_stop = E_stop
|
||||
|
||||
local safe = SRV_Channels:get_safety_state()
|
||||
if safe ~= last_safe then
|
||||
gcs:send_text(0, 'Safe state: ' .. tostring(safe))
|
||||
end
|
||||
last_safe = safe
|
||||
|
||||
return update, 100
|
||||
end
|
||||
|
||||
return update()
|
|
@ -279,6 +279,8 @@ singleton SRV_Channels method get_output_scaled float SRV_Channel::Aux_servo_fun
|
|||
singleton SRV_Channels method set_output_norm void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 float -1 1
|
||||
singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
||||
singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
||||
singleton SRV_Channels method get_emergency_stop boolean
|
||||
singleton SRV_Channels manual get_safety_state SRV_Channels_get_safety_state 0
|
||||
|
||||
ap_object RC_Channel method norm_input float
|
||||
ap_object RC_Channel method norm_input_dz float
|
||||
|
@ -521,6 +523,7 @@ singleton AP::motors() depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_CO
|
|||
singleton AP::motors() literal
|
||||
singleton AP::motors() rename motors
|
||||
singleton AP::motors() method set_frame_string void string
|
||||
singleton AP::motors() method get_interlock boolean
|
||||
|
||||
include AP_Common/AP_FWVersion.h
|
||||
singleton AP::fwversion() literal
|
||||
|
|
|
@ -532,3 +532,11 @@ int lua_removefile(lua_State *L) {
|
|||
const char *filename = luaL_checkstring(L, 1);
|
||||
return luaL_fileresult(L, remove(filename) == 0, filename);
|
||||
}
|
||||
|
||||
// Manual binding to allow SRV_Channels table to see safety state
|
||||
int SRV_Channels_get_safety_state(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
const bool data = hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED;
|
||||
lua_pushboolean(L, data);
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -12,3 +12,4 @@ int lua_get_CAN_device(lua_State *L);
|
|||
int lua_get_CAN_device2(lua_State *L);
|
||||
int lua_dirlist(lua_State *L);
|
||||
int lua_removefile(lua_State *L);
|
||||
int SRV_Channels_get_safety_state(lua_State *L);
|
||||
|
|
Loading…
Reference in New Issue