Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: refresh serial bindings #27411

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 10 additions & 11 deletions libraries/AP_Scripting/AP_Scripting_SerialAccess.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ void AP_Scripting_SerialAccess::begin(uint32_t baud)
}
}

size_t AP_Scripting_SerialAccess::write(uint8_t c)
bool AP_Scripting_SerialAccess::write(uint8_t c)
{
return write(&c, 1);
return write(&c, 1) > 0;
}

size_t AP_Scripting_SerialAccess::write(const uint8_t *buffer, size_t size)
Expand All @@ -37,13 +37,9 @@ size_t AP_Scripting_SerialAccess::write(const uint8_t *buffer, size_t size)
return ON_DEVICE_PORT(write, buffer, size);
}

int16_t AP_Scripting_SerialAccess::read(void)
bool AP_Scripting_SerialAccess::read(uint8_t &c)
{
uint8_t c;
if (read(&c, 1) != 1) {
return -1;
}
return c;
return read(&c, 1) > 0;
}

ssize_t AP_Scripting_SerialAccess::read(uint8_t* buffer, uint16_t count)
Expand All @@ -54,12 +50,15 @@ ssize_t AP_Scripting_SerialAccess::read(uint8_t* buffer, uint16_t count)
return ON_DEVICE_PORT(read, buffer, count);
}

uint32_t AP_Scripting_SerialAccess::available(void)
int32_t AP_Scripting_SerialAccess::available(void)
{
uint32_t avail;
if (!check_is_device_port()) {
return stream->available();
avail = stream->available();
} else {
avail = ON_DEVICE_PORT(available);
}
return ON_DEVICE_PORT(available);
return MIN(avail, (uint32_t)INT32_MAX); // ensure result fits in a Lua integer
}

void AP_Scripting_SerialAccess::set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs)
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Scripting/AP_Scripting_SerialAccess.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,13 @@ class AP_Scripting_SerialAccess {

void begin(uint32_t baud);

size_t write(uint8_t c);
bool write(uint8_t c);
size_t write(const uint8_t *buffer, size_t size);

int16_t read(void);
bool read(uint8_t &c);
ssize_t read(uint8_t *buffer, uint16_t count);

uint32_t available(void);
int32_t available(void);

void set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs);

Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -1234,12 +1234,12 @@ function AP_HAL__I2CDevice_ud:set_retries(retries) end
local AP_Scripting_SerialAccess_ud = {}

-- Start serial port with the given baud rate (no effect for device ports)
---@param baud_rate uint32_t_ud|integer|number
---@param baud_rate integer
function AP_Scripting_SerialAccess_ud:begin(baud_rate) end

-- Writes a single byte
---@param value integer -- byte to write
---@return uint32_t_ud -- 1 if success else 0
---@return boolean -- true if successfully written
function AP_Scripting_SerialAccess_ud:write(value) end

-- Writes a string. The number of bytes actually written, i.e. the length of the
Expand All @@ -1250,7 +1250,7 @@ function AP_Scripting_SerialAccess_ud:write(value) end
function AP_Scripting_SerialAccess_ud:writestring(data) end

-- Reads a single byte from the serial port
---@return integer -- byte, -1 if error or none available
---@return integer|nil -- byte, or nil on error/none available
function AP_Scripting_SerialAccess_ud:read() end

-- Reads up to `count` bytes and returns the bytes read as a string. No bytes
Expand All @@ -1260,7 +1260,7 @@ function AP_Scripting_SerialAccess_ud:read() end
function AP_Scripting_SerialAccess_ud:readstring(count) end

-- Returns number of available bytes to read.
---@return uint32_t_ud
---@return integer
function AP_Scripting_SerialAccess_ud:available() end

-- Set flow control option for serial port (no effect for device ports)
Expand Down
8 changes: 5 additions & 3 deletions libraries/AP_Scripting/drivers/EFI_DLA.lua
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,9 @@ end
local function read_bytes(n)
local ret = ""
for _ = 1, n do
ret = ret .. string.char(uart:read())
local b = uart:read()
assert(b)
ret = ret .. string.char(b)
end
return ret
end
Expand All @@ -88,7 +90,7 @@ state.total_fuel_cm3 = 0.0
check for input and parse data
--]]
local function check_input()
local n_bytes = uart:available():toint()
local n_bytes = uart:available()
--gcs:send_text(MAV_SEVERITY.INFO, string.format("n_bytes=%u %.2f", n_bytes, millis():tofloat()*0.001))
if n_bytes < 82 then
return
Expand All @@ -108,7 +110,7 @@ local function check_input()
state.last_read_us = micros()

-- discard the rest
discard_bytes(uart:available():toint())
discard_bytes(uart:available())
end

--[[
Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_Scripting/drivers/Generator_SVFFI.lua
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,9 @@ end
local function read_bytes(n)
local ret = ""
for _ = 1, n do
ret = ret .. string.char(uart:read())
local b = uart:read()
assert(b)
ret = ret .. string.char(b)
end
return ret
end
Expand Down Expand Up @@ -149,7 +151,7 @@ state.last_status = -1
check for input and parse data
--]]
local function check_input()
local n_bytes = uart:available():toint()
local n_bytes = uart:available()
--gcs:send_text(MAV_SEVERITY.INFO, string.format("n_bytes=%u %.2f", n_bytes, millis():tofloat()*0.001))
if n_bytes < 31 then
return
Expand Down
8 changes: 5 additions & 3 deletions libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,9 @@ uart:begin(115200)
local function read_bytes(n)
local ret = ""
for _ = 1, n do
ret = ret .. string.char(uart:read())
local b = uart:read()
assert(b)
ret = ret .. string.char(b)
end
return ret
end
Expand All @@ -76,7 +78,7 @@ end
discard pending bytes
--]]
local function discard_pending()
local n = uart:available():toint()
local n = uart:available()
for _ = 1, n do
uart:read()
end
Expand Down Expand Up @@ -168,7 +170,7 @@ local telem_data = ESCTelemetryData()
check for input and parse data
--]]
local function check_input()
local n_bytes = uart:available():toint()
local n_bytes = uart:available()
if n_bytes < 160 then
return
end
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_Scripting/drivers/INF_Inject.lua
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,7 @@ local function read_bytes(n)
local ret = ""
for _ = 1, n do
local b = uart:read()
assert(b)
state.chk0 = state.chk0 ~ b
state.chk1 = state.chk1 ~ state.chk0
ret = ret .. string.char(b)
Expand Down Expand Up @@ -168,7 +169,7 @@ end
--]]
local function check_input()
local packet_size = 83
local n_bytes = uart:available():toint()
local n_bytes = uart:available()
if n_bytes < packet_size then
return false
end
Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_Scripting/examples/readstring_test.lua
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ local function get_string_44(n)
local ret = ""
for _ = 1, n do
local b = port:read()
assert(b)
ret = ret .. string.char(b)
end
return ret
Expand All @@ -32,14 +33,14 @@ end

function update()
-- test using 4.5 method
local n = port:available():toint()
local n = port:available()
if n > 0 then
local str = get_string_45(n)
gcs:send_text(0, string.format("Received: '%s'", str))
end

-- test using 4.4 method (just so we don't have an unused function in lua check)
n = port:available():toint()
n = port:available()
if n > 0 then
local str = get_string_44(n)
gcs:send_text(0, string.format("Received: '%s'", str))
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -395,12 +395,12 @@ singleton RC_Channels method get_aux_cached boolean RC_Channel::AUX_FUNC'enum 0
include AP_Scripting/AP_Scripting_SerialAccess.h
-- don't let user create access objects
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 begin void int32_t 1 INT32_MAX
userdata AP_Scripting_SerialAccess method write boolean uint8_t'skip_check
userdata AP_Scripting_SerialAccess manual writestring lua_serial_writestring 1 1
userdata AP_Scripting_SerialAccess method read int16_t
userdata AP_Scripting_SerialAccess manual read lua_serial_read 0 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 available int32_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

-- serial is not a real C++ type here, but its name never gets used in C++ as we only have manual methods
Expand Down
26 changes: 21 additions & 5 deletions libraries/AP_Scripting/lua_bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -792,6 +792,7 @@ int lua_serial_writestring(lua_State *L)
// get the bytes the user wants to write, along with their length
size_t req_bytes;
const char *data = lua_tolstring(L, 2, &req_bytes);
req_bytes = MIN(req_bytes, (size_t)INT32_MAX); // ensure result fits in a Lua integer

// write up to that number of bytes
const uint32_t written_bytes = port->write((const uint8_t*)data, req_bytes);
Expand All @@ -802,6 +803,21 @@ int lua_serial_writestring(lua_State *L)
return 1;
}

int lua_serial_read(lua_State *L) {
binding_argcheck(L, 1);

AP_Scripting_SerialAccess * port = check_AP_Scripting_SerialAccess(L, 1);

uint8_t c;
if (port->read(c)) {
lua_pushinteger(L, c);
} else {
lua_pushnil(L); // error, return nil
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Return 0

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We have to push nil specifically so that we return a value. Otherwise e.g. string.char(port:read()) will return an empty string if there is no data available instead of raising an error that it tried to do something with nil. (Previously, it would raise an error that -1 is out of range).

}

return 1;
}

int lua_serial_readstring(lua_State *L) {
binding_argcheck(L, 2);

Expand All @@ -814,13 +830,13 @@ int lua_serial_readstring(lua_State *L) {

// 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
if (read_bytes >= 0) {
// push the buffer as a string, truncated to the number of bytes actually read
luaL_pushresultsize(&b, read_bytes);
} else {
lua_pushnil(L); // error, return nil
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can just return 0 in this case. No need to push nil.

Copy link
Contributor Author

@tpwrules tpwrules Jun 29, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Technically return 0 does not actually result in returning nil. It's not a big deal here but is more of a problem for port:read().

}

// push the buffer as a string, truncated to the number of bytes actually read
luaL_pushresultsize(&b, read_bytes);

return 1;
}

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Scripting/lua_bindings.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ int lua_get_CAN_device2(lua_State *L);
int lua_serial_find_serial(lua_State *L);
int lua_serial_find_simulated_device(lua_State *L);
int lua_serial_writestring(lua_State *L);
int lua_serial_read(lua_State *L);
int lua_serial_readstring(lua_State *L);
int lua_dirlist(lua_State *L);
int lua_removefile(lua_State *L);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/tests/serial_loopback.lua
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ function test_driver_to_device()
local msg_send = "hello device"
local num_sent = 0
for ci = 1,#msg_send do
num_sent = num_sent + ser_driver:write(msg_send:byte(ci, ci)):toint()
num_sent = num_sent + (ser_driver:write(msg_send:byte(ci, ci)) and 1 or 0)
end
local msg_recv = ser_device:readstring(#msg_send)
if msg_send == msg_recv and num_sent == #msg_send then
Expand Down
Loading