AP_Scripting: fixed a memory leak in socket recv()

we need to allocate the memory in the lua heap, otherwise a failure
leaks global memory
This commit is contained in:
Andrew Tridgell
2025-09-04 13:04:56 +01:00
parent 7a4ee4297b
commit 691e559db4

View File

@@ -1003,21 +1003,23 @@ int SocketAPM_recv(lua_State *L) {
SocketAPM * ud = *check_SocketAPM(L, 1);
const uint16_t count = get_uint16_t(L, 2);
uint8_t *data = (uint8_t*)malloc(count);
if (data == nullptr) {
return 0;
}
// create a buffer sized to hold the number of bytes the user
// wants to read. This will fault if the memory is not available
luaL_Buffer b;
uint8_t *data = (uint8_t *)luaL_buffinitsize(L, &b, count);
// read up to that number of bytes
const auto ret = ud->recv(data, count, 0);
if (ret < 0) {
free(data);
return 0;
return 0; // error, return nil
}
int retcount = 1;
// push data to lua string
lua_pushlstring(L, (const char *)data, ret);
// push the buffer as a string, truncated to the number of bytes
// actually read
luaL_pushresultsize(&b, ret);
// also push the address and port if available
uint32_t ip_addr;
@@ -1028,8 +1030,6 @@ int SocketAPM_recv(lua_State *L) {
retcount += 2;
}
free(data);
return retcount;
}