From 6a16bce001b7f2974878616d59fee81236390555 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 29 Sep 2024 14:06:29 +1000 Subject: [PATCH] AP_Scripting: added bindings for IPv4 address/string and make socket recv return the source address and port --- .../generator/description/bindings.desc | 5 ++- libraries/AP_Scripting/lua_bindings.cpp | 41 ++++++++++++++++++- libraries/AP_Scripting/lua_bindings.h | 2 + 3 files changed, 45 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 08c0abe185..5a1b52817c 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -599,11 +599,14 @@ 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 Socket lua_get_SocketAPM 1 1 depends (AP_NETWORKING_ENABLED==1) +global manual ipv4_addr_to_string SocketAPM_ipv4_addr_to_string 1 1 depends (AP_NETWORKING_ENABLED==1) +global manual string_to_ipv4_addr SocketAPM_string_to_ipv4_addr 1 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 ap_object SocketAPM method bind boolean string uint16_t'skip_check ap_object SocketAPM method send int32_t string uint32_t'skip_check +ap_object SocketAPM method sendto int32_t string uint32_t'skip_check uint32_t'skip_check uint16_t'skip_check ap_object SocketAPM method listen boolean uint8_t'skip_check ap_object SocketAPM method set_blocking boolean boolean ap_object SocketAPM method is_connected boolean @@ -612,7 +615,7 @@ ap_object SocketAPM method pollin boolean uint32_t'skip_check ap_object SocketAPM method reuseaddress boolean ap_object SocketAPM manual sendfile SocketAPM_sendfile 1 1 ap_object SocketAPM manual close SocketAPM_close 0 0 -ap_object SocketAPM manual recv SocketAPM_recv 1 1 +ap_object SocketAPM manual recv SocketAPM_recv 1 3 ap_object SocketAPM manual accept SocketAPM_accept 0 1 ap_object AP_HAL::AnalogSource depends !defined(HAL_DISABLE_ADC_DRIVER) diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 269eceedfa..0004c6c3f3 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -1004,11 +1004,23 @@ int SocketAPM_recv(lua_State *L) { return 0; } - // push to lua string + int retcount = 1; + + // push data to lua string lua_pushlstring(L, (const char *)data, ret); + + // also push the address and port if available + uint32_t ip_addr; + uint16_t port; + if (ud->last_recv_address(ip_addr, port)) { + *new_uint32_t(L) = ip_addr; + lua_pushinteger(L, port); + retcount += 2; + } + free(data); - return 1; + return retcount; } /* @@ -1037,6 +1049,31 @@ int SocketAPM_accept(lua_State *L) { return 0; } +/* + convert a uint32_t ipv4 address to a string + */ +int SocketAPM_ipv4_addr_to_string(lua_State *L) { + binding_argcheck(L, 1); + const uint32_t ip_addr = get_uint32(L, 1, 0, UINT32_MAX); + char buf[IP4_STR_LEN]; + const char *ret = SocketAPM::inet_addr_to_str(ip_addr, buf, sizeof(buf)); + if (ret == nullptr) { + return 0; + } + lua_pushlstring(L, (const char *)ret, strlen(ret)); + return 1; +} + +/* + convert a ipv4 string address to a uint32_t + */ +int SocketAPM_string_to_ipv4_addr(lua_State *L) { + binding_argcheck(L, 1); + const char *str = luaL_checkstring(L, 1); + *new_uint32_t(L) = SocketAPM::inet_str_to_addr(str); + return 1; +} + #endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 1c6a8358c3..b0a7e2c36b 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -24,6 +24,8 @@ int SocketAPM_recv(lua_State *L); int SocketAPM_accept(lua_State *L); int SocketAPM_close(lua_State *L); int SocketAPM_sendfile(lua_State *L); +int SocketAPM_ipv4_addr_to_string(lua_State *L); +int SocketAPM_string_to_ipv4_addr(lua_State *L); int lua_mavlink_init(lua_State *L); int lua_mavlink_receive_chan(lua_State *L); int lua_mavlink_register_rx_msgid(lua_State *L);