mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Scripting: refactor serial readstring
Using `luaL_Buffer` avoids the need for any heap allocation in the common case (count <= 512 bytes) and avoids stressing out the system heap for large reads, instead using the script heap. Zero net flash usage change.
This commit is contained in:
parent
e18449b1b8
commit
d93aa15f2a
@ -398,7 +398,7 @@ userdata AP_Scripting_SerialAccess creation null -1
|
||||
userdata AP_Scripting_SerialAccess method begin void uint32_t 1U UINT32_MAX
|
||||
userdata AP_Scripting_SerialAccess method write uint32_t uint8_t'skip_check
|
||||
userdata AP_Scripting_SerialAccess method read int16_t
|
||||
userdata AP_Scripting_SerialAccess manual readstring AP_Scripting_SerialAccess_readstring 1 1
|
||||
userdata AP_Scripting_SerialAccess manual readstring lua_serial_readstring 1 1
|
||||
userdata AP_Scripting_SerialAccess method available uint32_t
|
||||
userdata AP_Scripting_SerialAccess method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_RTS_DE
|
||||
|
||||
|
@ -655,30 +655,6 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L) {
|
||||
return success;
|
||||
}
|
||||
|
||||
int AP_Scripting_SerialAccess_readstring(lua_State *L) {
|
||||
binding_argcheck(L, 2);
|
||||
|
||||
AP_Scripting_SerialAccess * p = check_AP_Scripting_SerialAccess(L, 1);
|
||||
|
||||
const uint16_t count = get_uint16_t(L, 2);
|
||||
uint8_t *data = (uint8_t*)malloc(count);
|
||||
if (data == nullptr) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
const auto ret = p->read(data, count);
|
||||
if (ret < 0) {
|
||||
free(data);
|
||||
return 0;
|
||||
}
|
||||
|
||||
// push to lua string
|
||||
lua_pushlstring(L, (const char *)data, ret);
|
||||
free(data);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
#if AP_SCRIPTING_CAN_SENSOR_ENABLED
|
||||
int lua_get_CAN_device(lua_State *L) {
|
||||
|
||||
@ -767,6 +743,28 @@ int lua_serial_find_serial(lua_State *L) {
|
||||
}
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
||||
int lua_serial_readstring(lua_State *L) {
|
||||
binding_argcheck(L, 2);
|
||||
|
||||
AP_Scripting_SerialAccess * port = check_AP_Scripting_SerialAccess(L, 1);
|
||||
|
||||
// create a buffer sized to hold the number of bytes the user wants to read
|
||||
luaL_Buffer b;
|
||||
const uint16_t req_bytes = get_uint16_t(L, 2);
|
||||
uint8_t *data = (uint8_t *)luaL_buffinitsize(L, &b, req_bytes);
|
||||
|
||||
// read up to that number of bytes
|
||||
const ssize_t read_bytes = port->read(data, req_bytes);
|
||||
if (read_bytes < 0) {
|
||||
return 0; // error, return nil
|
||||
}
|
||||
|
||||
// push the buffer as a string, truncated to the number of bytes actually read
|
||||
luaL_pushresultsize(&b, read_bytes);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
directory listing, return table of files in a directory
|
||||
*/
|
||||
|
@ -8,10 +8,10 @@ int lua_mission_receive(lua_State *L);
|
||||
int AP_Logger_Write(lua_State *L);
|
||||
int lua_get_i2c_device(lua_State *L);
|
||||
int AP_HAL__I2CDevice_read_registers(lua_State *L);
|
||||
int AP_Scripting_SerialAccess_readstring(lua_State *L);
|
||||
int lua_get_CAN_device(lua_State *L);
|
||||
int lua_get_CAN_device2(lua_State *L);
|
||||
int lua_serial_find_serial(lua_State *L);
|
||||
int lua_serial_readstring(lua_State *L);
|
||||
int lua_dirlist(lua_State *L);
|
||||
int lua_removefile(lua_State *L);
|
||||
int SRV_Channels_get_safety_state(lua_State *L);
|
||||
|
Loading…
Reference in New Issue
Block a user