mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Scripting: updated docs
This commit is contained in:
parent
18044a9644
commit
583c24d833
@ -457,46 +457,77 @@ function motor_factor_table_ud:roll(index, value) end
|
||||
local SocketAPM_ud = {}
|
||||
|
||||
-- desc
|
||||
function SocketAPM(param1) end
|
||||
|
||||
-- return true if a socket is connected
|
||||
---@return boolean
|
||||
function SocketAPM_ud:is_connected() end
|
||||
|
||||
-- desc
|
||||
---@param param1 boolean
|
||||
-- set blocking state of socket
|
||||
---@param blocking boolean
|
||||
---@return boolean
|
||||
function SocketAPM_ud:set_blocking(param1) end
|
||||
function SocketAPM_ud:set_blocking(blocking) end
|
||||
|
||||
-- desc
|
||||
---@param param1 integer
|
||||
-- setup a socket to listen
|
||||
---@param backlog integer
|
||||
---@return boolean
|
||||
function SocketAPM_ud:listen(param1) end
|
||||
function SocketAPM_ud:listen(backlog) end
|
||||
|
||||
-- desc
|
||||
---@param param1 string
|
||||
---@param param2 uint32_t_ud
|
||||
-- send a lua string. May contain binary data
|
||||
---@param str string
|
||||
---@param len uint32_t_ud
|
||||
---@return integer
|
||||
function SocketAPM_ud:send(param1, param2) end
|
||||
function SocketAPM_ud:send(str, len) end
|
||||
|
||||
-- desc
|
||||
---@param param1 string
|
||||
---@param param2 integer
|
||||
-- bind to an address. Use "0.0.0.0" for wildcard bind
|
||||
---@param IP_address string
|
||||
---@param port integer
|
||||
---@return boolean
|
||||
function SocketAPM_ud:bind(param1, param2) end
|
||||
function SocketAPM_ud:bind(IP_address, port) end
|
||||
|
||||
-- desc
|
||||
---@param param1 string
|
||||
---@param param2 integer
|
||||
-- connect a socket to an endpoint
|
||||
---@param IP_address string
|
||||
---@param port integer
|
||||
---@return boolean
|
||||
function SocketAPM_ud:connect(param1, param2) end
|
||||
function SocketAPM_ud:connect(IP_address, port) end
|
||||
|
||||
-- desc
|
||||
function SocketAPM_ud:__gc() end
|
||||
|
||||
-- desc
|
||||
--[[ accept new incoming sockets, returning a new socket.
|
||||
Must be used on a stream socket in listen state
|
||||
--]]
|
||||
function SocketAPM_ud:accept(param1) end
|
||||
|
||||
-- desc
|
||||
function SocketAPM_ud:recv(param1) end
|
||||
-- receive data from a socket
|
||||
---@param length
|
||||
---@return data
|
||||
function SocketAPM_ud:recv(length) end
|
||||
|
||||
-- check for available input
|
||||
---@param timeout_ms uint32_t_ud
|
||||
---@return boolean
|
||||
function SocketAPM_ud:pollin(timeout_ms) end
|
||||
|
||||
-- check for availability of space to write to socket
|
||||
---@param timeout_ms uint32_t_ud
|
||||
---@return boolean
|
||||
function SocketAPM_ud:pollout(timeout_ms) end
|
||||
|
||||
--[[
|
||||
close a socket. Note that there is no automatic garbage
|
||||
collection of sockets so you must close a socket when you are
|
||||
finished with it or you will run out of sockets
|
||||
--]]
|
||||
function SocketAPM_ud:close() end
|
||||
|
||||
--[[
|
||||
setup to send all remaining data from a filehandle to the socket
|
||||
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
|
||||
--]]
|
||||
function SocketAPM_ud:sendfile(filehandle) end
|
||||
|
||||
-- enable SO_REUSEADDR on a socket
|
||||
---@return boolean
|
||||
function SocketAPM_ud:reuseaddress() end
|
||||
|
||||
-- desc
|
||||
---@class AP_HAL__PWMSource_ud
|
||||
@ -3111,3 +3142,68 @@ function fence:get_breach_time() end
|
||||
---| 4 # Polygon
|
||||
---| 8 # Minimum altitude
|
||||
function fence:get_breaches() end
|
||||
|
||||
-- desc
|
||||
---@class stat_t_ud
|
||||
local stat_t_ud = {}
|
||||
|
||||
---@return stat_t_ud
|
||||
function stat_t() end
|
||||
|
||||
-- get creation time in seconds
|
||||
---@return uint32_t_ud
|
||||
function stat_t_ud:ctime() end
|
||||
|
||||
-- get last access time in seconds
|
||||
---@return uint32_t_ud
|
||||
function stat_t_ud:atime() end
|
||||
|
||||
-- get last modification time in seconds
|
||||
---@return uint32_t_ud
|
||||
function stat_t_ud:mtime() end
|
||||
|
||||
-- get file mode
|
||||
---@return integer
|
||||
function stat_t_ud:mode() end
|
||||
|
||||
-- get file size in bytes
|
||||
---@return uint32_t_ud
|
||||
function stat_t_ud:size() end
|
||||
|
||||
-- return true if this is a directory
|
||||
---@return boolean
|
||||
function stat_t_ud:is_directory() end
|
||||
|
||||
-- desc
|
||||
---@class rtc
|
||||
rtc = {}
|
||||
|
||||
-- return a time since 1970 in seconds from GMT date elements
|
||||
---@param year integer -- 20xx
|
||||
---@param month integer -- 0-11
|
||||
---@param day integer -- 1-31
|
||||
---@param hour integer -- 0-23
|
||||
---@param min integer -- 0-60
|
||||
---@param sec integer -- 0-60
|
||||
---@return uint32_t_ud
|
||||
function rtc:date_fields_to_clock_s(year, month, day, hour, min, sec) end
|
||||
|
||||
-- break a time in seconds since 1970 to GMT date elements
|
||||
---@param param1 uint32_t_ud
|
||||
---@return integer|nil -- year 20xx
|
||||
---@return integer|nil -- month 0-11
|
||||
---@return integer|nil -- day 1-31
|
||||
---@return integer|nil -- hour 0-23
|
||||
---@return integer|nil -- min 0-60
|
||||
---@return integer|nil -- sec 0-60
|
||||
---@return integer|nil -- weekday 0-6, sunday is 0
|
||||
function rtc:clock_s_to_date_fields(param1) end
|
||||
|
||||
-- desc
|
||||
---@class fs
|
||||
fs = {}
|
||||
|
||||
-- desc
|
||||
---@param param1 string
|
||||
---@return stat_t_ud|nil
|
||||
function fs:stat(param1) end
|
||||
|
Loading…
Reference in New Issue
Block a user