diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 1197c502c8..0a689dd344 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -2830,9 +2830,21 @@ function vehicle:set_crosstrack_start(new_start_location) end ---@param number integer -- mode number to use, should be over 100 ---@param full_name string -- Full mode name ---@param short_name string -- Short mode name upto 4 characters ----@return boolean -- true if successful +---@return AP_Vehicle__custom_mode_state_ud|nil -- Returns custom mode state which allows customisation of behavior, nil if mode register fails function vehicle:register_custom_mode(number, full_name, short_name) end +-- Custom mode state, allows customisation of mode behavior +---@class (exact) AP_Vehicle__custom_mode_state_ud +local AP_Vehicle__custom_mode_state_ud = {} + +-- get allow_entry, if true the vehicle is allowed to enter this custom mode +---@return boolean +function AP_Vehicle__custom_mode_state_ud:allow_entry() end + +-- set allow_entry, if true the vehicle is allowed to enter this custom mode +---@param value boolean +function AP_Vehicle__custom_mode_state_ud:allow_entry(value) end + -- desc onvif = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 234b2dbd78..0a2653a55b 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -309,6 +309,9 @@ singleton AP_ONVIF method set_absolutemove boolean float'skip_check float'skip_c singleton AP_ONVIF method get_pan_tilt_limit_min Vector2f singleton AP_ONVIF method get_pan_tilt_limit_max Vector2f +ap_object AP_Vehicle::custom_mode_state depends (!defined(HAL_BUILD_AP_PERIPH)) +ap_object AP_Vehicle::custom_mode_state field allow_entry boolean read write + include AP_Vehicle/AP_Vehicle.h singleton AP_Vehicle depends (!defined(HAL_BUILD_AP_PERIPH)) singleton AP_Vehicle rename vehicle @@ -352,7 +355,7 @@ singleton AP_Vehicle method reboot void boolean singleton AP_Vehicle method is_landing boolean singleton AP_Vehicle method is_taking_off boolean singleton AP_Vehicle method set_crosstrack_start boolean Location -singleton AP_Vehicle method register_custom_mode boolean uint8_t'skip_check string string +singleton AP_Vehicle method register_custom_mode AP_Vehicle::custom_mode_state uint8_t'skip_check string string include AP_SerialLED/AP_SerialLED.h