AP_Scripting: review fixes
thanks Pete!
This commit is contained in:
parent
867e9c6799
commit
ffb7328ede
@ -71,7 +71,7 @@ local BRD_RTC_TZ_MIN = Parameter("BRD_RTC_TZ_MIN")
|
||||
|
||||
gcs:send_text(MAV_SEVERITY.INFO, string.format("WebServer: starting on port %u", WEB_BIND_PORT:get()))
|
||||
|
||||
local sock_listen = SocketAPM(0)
|
||||
local sock_listen = Socket(0)
|
||||
local clients = {}
|
||||
|
||||
local DOCTYPE = "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 3.2 Final//EN\">"
|
||||
|
@ -457,7 +457,7 @@ function motor_factor_table_ud:roll(index, value) end
|
||||
local SocketAPM_ud = {}
|
||||
|
||||
-- desc
|
||||
function SocketAPM(param1) end
|
||||
function Socket(param1) end
|
||||
|
||||
-- return true if a socket is connected
|
||||
---@return boolean
|
||||
|
@ -44,11 +44,11 @@ local function test_ip()
|
||||
end
|
||||
|
||||
local counter = 0
|
||||
local sock_tcp_echo = SocketAPM(0)
|
||||
local sock_udp_echo = SocketAPM(1)
|
||||
local sock_tcp_in = SocketAPM(0)
|
||||
local sock_tcp_echo = Socket(0)
|
||||
local sock_udp_echo = Socket(1)
|
||||
local sock_tcp_in = Socket(0)
|
||||
local sock_tcp_in2 = nil
|
||||
local sock_udp_in = SocketAPM(1)
|
||||
local sock_udp_in = Socket(1)
|
||||
|
||||
assert(sock_tcp_echo, "net_test: failed to create tcp echo socket")
|
||||
assert(sock_udp_echo, "net_test: failed to create udp echo socket")
|
||||
|
@ -537,7 +537,7 @@ ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registe
|
||||
ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check
|
||||
|
||||
include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1)
|
||||
global manual SocketAPM lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1)
|
||||
global manual Socket lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1)
|
||||
|
||||
ap_object SocketAPM depends (AP_NETWORKING_ENABLED==1)
|
||||
ap_object SocketAPM method connect boolean string uint16_t'skip_check
|
||||
|
@ -770,8 +770,6 @@ int lua_get_SocketAPM(lua_State *L) {
|
||||
const uint8_t datagram = get_uint8_t(L, 1);
|
||||
auto *scripting = AP::scripting();
|
||||
|
||||
lua_gc(L, LUA_GCCOLLECT, 0);
|
||||
|
||||
if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) {
|
||||
return luaL_argerror(L, 1, "no sockets available");
|
||||
}
|
||||
@ -829,7 +827,7 @@ int SocketAPM_sendfile(lua_State *L) {
|
||||
auto *scripting = AP::scripting();
|
||||
|
||||
if (scripting->num_net_sockets == 0) {
|
||||
return luaL_argerror(L, 1, "socket close error");
|
||||
return luaL_argerror(L, 1, "sendfile error");
|
||||
}
|
||||
|
||||
auto *p = (luaL_Stream *)luaL_checkudata(L, 2, LUA_FILEHANDLE);
|
||||
|
Loading…
Reference in New Issue
Block a user