mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Docs: fix all type errors
This commit is contained in:
parent
a4a8923e1e
commit
aa7a1ce2a6
|
@ -526,6 +526,8 @@ function SocketAPM_ud:close() end
|
||||||
this also "closes" the socket and the file from the point of view of lua
|
this also "closes" the socket and the file from the point of view of lua
|
||||||
the underlying socket and file are both closed on end of file
|
the underlying socket and file are both closed on end of file
|
||||||
--]]
|
--]]
|
||||||
|
---@param filehandle string
|
||||||
|
---@return boolean -- success
|
||||||
function SocketAPM_ud:sendfile(filehandle) end
|
function SocketAPM_ud:sendfile(filehandle) end
|
||||||
|
|
||||||
-- enable SO_REUSEADDR on a socket
|
-- enable SO_REUSEADDR on a socket
|
||||||
|
@ -1847,7 +1849,7 @@ function mission:get_last_jump_tag() end
|
||||||
function mission:jump_to_landing_sequence() end
|
function mission:jump_to_landing_sequence() end
|
||||||
|
|
||||||
-- Jump to the landing abort sequence
|
-- Jump to the landing abort sequence
|
||||||
-- @return boolean
|
---@return boolean
|
||||||
function mission:jump_to_abort_landing_sequence() end
|
function mission:jump_to_abort_landing_sequence() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
|
@ -2060,7 +2062,7 @@ function rc:run_aux_function(aux_fun, ch_flag) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param aux_fun integer
|
---@param aux_fun integer
|
||||||
---@return RC_Channel_ud
|
---@return RC_Channel_ud|nil
|
||||||
function rc:find_channel_for_option(aux_fun) end
|
function rc:find_channel_for_option(aux_fun) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
|
@ -2370,10 +2372,12 @@ function vehicle:set_target_throttle_rate_rpy(param1, param2, param3, param4) en
|
||||||
function vehicle:nav_script_time_done(param1) end
|
function vehicle:nav_script_time_done(param1) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@return integer|nil
|
---@return integer|nil -- id
|
||||||
---@return integer|nil
|
---@return integer|nil -- cmd
|
||||||
---@return number|nil
|
---@return number|nil -- arg1
|
||||||
---@return number|nil
|
---@return number|nil -- arg2
|
||||||
|
---@return integer|nil -- arg3
|
||||||
|
---@return integer|nil -- arg4
|
||||||
function vehicle:nav_script_time() end
|
function vehicle:nav_script_time() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
|
@ -2577,27 +2581,27 @@ local RangeFinder_State_ud = {}
|
||||||
function RangeFinder_State() end
|
function RangeFinder_State() end
|
||||||
|
|
||||||
-- get system time (ms) of last successful update from sensor
|
-- get system time (ms) of last successful update from sensor
|
||||||
---@return number
|
---@return uint32_t_ud
|
||||||
function RangeFinder_State_ud:last_reading() end
|
function RangeFinder_State_ud:last_reading() end
|
||||||
|
|
||||||
-- set system time (ms) of last successful update from sensor
|
-- set system time (ms) of last successful update from sensor
|
||||||
---@param value number
|
---@param value uint32_t_ud
|
||||||
function RangeFinder_State_ud:last_reading(value) end
|
function RangeFinder_State_ud:last_reading(value) end
|
||||||
|
|
||||||
-- get sensor status
|
-- get sensor status
|
||||||
---@return number
|
---@return integer
|
||||||
function RangeFinder_State_ud:status() end
|
function RangeFinder_State_ud:status() end
|
||||||
|
|
||||||
-- set sensor status
|
-- set sensor status
|
||||||
---@param value number
|
---@param value integer
|
||||||
function RangeFinder_State_ud:status(value) end
|
function RangeFinder_State_ud:status(value) end
|
||||||
|
|
||||||
-- get number of consecutive valid readings (max out at 10)
|
-- get number of consecutive valid readings (max out at 10)
|
||||||
---@return number
|
---@return integer
|
||||||
function RangeFinder_State_ud:range_valid_count() end
|
function RangeFinder_State_ud:range_valid_count() end
|
||||||
|
|
||||||
-- set number of consecutive valid readings (max out at 10)
|
-- set number of consecutive valid readings (max out at 10)
|
||||||
---@param value number
|
---@param value integer
|
||||||
function RangeFinder_State_ud:range_valid_count(value) end
|
function RangeFinder_State_ud:range_valid_count(value) end
|
||||||
|
|
||||||
-- get distance in meters
|
-- get distance in meters
|
||||||
|
@ -2609,19 +2613,19 @@ function RangeFinder_State_ud:distance() end
|
||||||
function RangeFinder_State_ud:distance(value) end
|
function RangeFinder_State_ud:distance(value) end
|
||||||
|
|
||||||
-- get measurement quality in percent 0-100, -1 -> quality is unknown
|
-- get measurement quality in percent 0-100, -1 -> quality is unknown
|
||||||
---@return number
|
---@return integer
|
||||||
function RangeFinder_State_ud:signal_quality() end
|
function RangeFinder_State_ud:signal_quality() end
|
||||||
|
|
||||||
-- set measurement quality in percent 0-100, -1 -> quality is unknown
|
-- set measurement quality in percent 0-100, -1 -> quality is unknown
|
||||||
---@param value number
|
---@param value integer
|
||||||
function RangeFinder_State_ud:signal_quality(value) end
|
function RangeFinder_State_ud:signal_quality(value) end
|
||||||
|
|
||||||
-- get voltage in millivolts, if applicable, otherwise 0
|
-- get voltage in millivolts, if applicable, otherwise 0
|
||||||
---@return number
|
---@return integer
|
||||||
function RangeFinder_State_ud:voltage() end
|
function RangeFinder_State_ud:voltage() end
|
||||||
|
|
||||||
-- set voltage in millivolts, if applicable, otherwise 0
|
-- set voltage in millivolts, if applicable, otherwise 0
|
||||||
---@param value number
|
---@param value integer
|
||||||
function RangeFinder_State_ud:voltage(value) end
|
function RangeFinder_State_ud:voltage(value) end
|
||||||
|
|
||||||
|
|
||||||
|
@ -3325,11 +3329,15 @@ function scripting:restart_all() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param directoryname string
|
---@param directoryname string
|
||||||
---@return table -- table of filenames
|
---@return table|nil -- table of filenames
|
||||||
|
---@return string|nil -- error string if fails
|
||||||
function dirlist(directoryname) end
|
function dirlist(directoryname) end
|
||||||
|
|
||||||
--desc
|
--desc
|
||||||
---@param filename string
|
---@param filename string
|
||||||
|
---@return boolean|nil -- true on success
|
||||||
|
---@return nil|string -- error string
|
||||||
|
---@return integer -- error number
|
||||||
function remove(filename) end
|
function remove(filename) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
|
@ -3343,6 +3351,7 @@ function mavlink:init(num_rx_msgid, msg_queue_length) end
|
||||||
|
|
||||||
-- marks mavlink message for receive, message id can be get using mavlink_msgs.get_msgid("MSG_NAME")
|
-- marks mavlink message for receive, message id can be get using mavlink_msgs.get_msgid("MSG_NAME")
|
||||||
---@param msg_id number
|
---@param msg_id number
|
||||||
|
---@return boolean -- false if id has been registered already
|
||||||
function mavlink:register_rx_msgid(msg_id) end
|
function mavlink:register_rx_msgid(msg_id) end
|
||||||
|
|
||||||
-- receives mavlink message marked for receive using mavlink:register_rx_msgid
|
-- receives mavlink message marked for receive using mavlink:register_rx_msgid
|
||||||
|
@ -3356,10 +3365,12 @@ function mavlink:receive_chan() end
|
||||||
---@param chan integer
|
---@param chan integer
|
||||||
---@param msgid integer
|
---@param msgid integer
|
||||||
---@param message string
|
---@param message string
|
||||||
|
---@return boolean -- success
|
||||||
function mavlink:send_chan(chan, msgid, message) end
|
function mavlink:send_chan(chan, msgid, message) end
|
||||||
|
|
||||||
-- Block a given MAV_CMD from being procceced by ArduPilot
|
-- Block a given MAV_CMD from being procceced by ArduPilot
|
||||||
---@param comand_id integer
|
---@param comand_id integer
|
||||||
|
---@return boolean
|
||||||
function mavlink:block_command(comand_id) end
|
function mavlink:block_command(comand_id) end
|
||||||
|
|
||||||
-- Geofence library
|
-- Geofence library
|
||||||
|
@ -3416,8 +3427,8 @@ rtc = {}
|
||||||
-- return a time since 1970 in seconds from GMT date elements
|
-- return a time since 1970 in seconds from GMT date elements
|
||||||
---@param year integer -- 20xx
|
---@param year integer -- 20xx
|
||||||
---@param month integer -- 0-11
|
---@param month integer -- 0-11
|
||||||
---@param day integer -- 1-31
|
---@param day integer -- 1-31
|
||||||
---@param hour integer -- 0-23
|
---@param hour integer -- 0-23
|
||||||
---@param min integer -- 0-60
|
---@param min integer -- 0-60
|
||||||
---@param sec integer -- 0-60
|
---@param sec integer -- 0-60
|
||||||
---@return uint32_t_ud
|
---@return uint32_t_ud
|
||||||
|
@ -3448,10 +3459,11 @@ function fs:stat(param1) end
|
||||||
function fs:format() end
|
function fs:format() end
|
||||||
|
|
||||||
-- Get the current status of a format. 0=NOT_STARTED, 1=PENDING, 2=IN_PROGRESS, 3=SUCCESS, 4=FAILURE
|
-- Get the current status of a format. 0=NOT_STARTED, 1=PENDING, 2=IN_PROGRESS, 3=SUCCESS, 4=FAILURE
|
||||||
---@return number
|
---@return integer
|
||||||
function fs:get_format_status() end
|
function fs:get_format_status() end
|
||||||
|
|
||||||
-- Get crc32 checksum of a file with given name
|
-- Get crc32 checksum of a file with given name
|
||||||
|
---@param file_name string
|
||||||
---@return uint32_t_ud|nil
|
---@return uint32_t_ud|nil
|
||||||
function fs:crc32(file_name) end
|
function fs:crc32(file_name) end
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue