AP_Scripting: use generic access userdata for serial ports

Adding another layer instead of just exposing UARTDriver bindings allows
substitution of the different functions for device simulation later.

Also take the opportunity to rework the docs a little.
This commit is contained in:
Thomas Watson 2024-06-16 14:33:23 -05:00 committed by Peter Barker
parent c37dba60de
commit e18449b1b8
6 changed files with 148 additions and 49 deletions

View File

@ -0,0 +1,49 @@
/*
generic object to allow a script to use a serial stream
*/
#include "AP_Scripting_config.h"
#include "AP_Scripting_SerialAccess.h"
#if AP_SCRIPTING_ENABLED
void AP_Scripting_SerialAccess::begin(uint32_t baud)
{
stream->begin(baud);
}
size_t AP_Scripting_SerialAccess::write(uint8_t c)
{
return write(&c, 1);
}
size_t AP_Scripting_SerialAccess::write(const uint8_t *buffer, size_t size)
{
return stream->write(buffer, size);
}
int16_t AP_Scripting_SerialAccess::read(void)
{
uint8_t c;
if (read(&c, 1) != 1) {
return -1;
}
return c;
}
ssize_t AP_Scripting_SerialAccess::read(uint8_t* buffer, uint16_t count)
{
return stream->read(buffer, count);
}
uint32_t AP_Scripting_SerialAccess::available(void)
{
return stream->available();
}
void AP_Scripting_SerialAccess::set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs)
{
stream->set_flow_control(fcs);
}
#endif // AP_SCRIPTING_ENABLED

View File

@ -0,0 +1,25 @@
#pragma once
#include <AP_HAL/UARTDriver.h>
class AP_Scripting_SerialAccess {
public:
/* Do not allow copies */
CLASS_NO_COPY(AP_Scripting_SerialAccess);
AP_Scripting_SerialAccess() {}
void begin(uint32_t baud);
size_t write(uint8_t c);
size_t write(const uint8_t *buffer, size_t size);
int16_t read(void);
ssize_t read(uint8_t *buffer, uint16_t count);
uint32_t available(void);
void set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs);
AP_HAL::UARTDriver *stream;
};

View File

@ -1229,41 +1229,39 @@ function AP_HAL__I2CDevice_ud:write_register(register_num, value) end
function AP_HAL__I2CDevice_ud:set_retries(retries) end
-- Serial driver object
---@class (exact) AP_HAL__UARTDriver_ud
local AP_HAL__UARTDriver_ud = {}
-- Serial port access object
---@class (exact) AP_Scripting_SerialAccess_ud
local AP_Scripting_SerialAccess_ud = {}
-- Start serial port with the given baud rate
---@param baud_rate uint32_t_ud|integer|number
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
function AP_Scripting_SerialAccess_ud:write(value) end
-- Reads a single byte from the serial port
---@return integer -- byte, -1 if error or none available
function AP_Scripting_SerialAccess_ud:read() end
-- Reads up to `count` bytes and returns the bytes read as a string. No bytes
-- may be read, in which case a 0-length string is returned.
---@param count integer -- maximum number of bytes to read
---@return string|nil -- bytes actually read, which may be 0-length, or nil on error
function AP_Scripting_SerialAccess_ud:readstring(count) end
-- Returns number of available bytes to read.
---@return uint32_t_ud
function AP_Scripting_SerialAccess_ud:available() end
-- Set flow control option for serial port
---@param flow_control_setting integer
---| '0' # disabled
---| '1' # enabled
---| '2' # auto
function AP_HAL__UARTDriver_ud:set_flow_control(flow_control_setting) end
-- Returns number of available bytes to read.
---@return uint32_t_ud
function AP_HAL__UARTDriver_ud:available() end
-- Writes a single byte
---@param value integer -- byte to write
---@return uint32_t_ud -- 1 if success else 0
function AP_HAL__UARTDriver_ud:write(value) end
-- Read a single byte from the serial port
---@return integer -- byte, -1 if not available
function AP_HAL__UARTDriver_ud:read() end
-- Start serial port with given baud rate
---@param baud_rate uint32_t_ud|integer|number
function AP_HAL__UARTDriver_ud:begin(baud_rate) end
--[[
read count bytes from a uart and return as a lua string. Note
that the returned string can be shorter than the requested length
--]]
---@param count integer
---@return string|nil
function AP_HAL__UARTDriver_ud:readstring(count) end
function AP_Scripting_SerialAccess_ud:set_flow_control(flow_control_setting) end
-- desc
@ -2106,11 +2104,12 @@ function baro:healthy(instance) end
-- Serial ports
serial = {}
-- Returns the UART instance that allows connections from scripts (those with SERIALx_PROTOCOL = 28).
-- For instance = 0, returns first such UART, second for instance = 1, and so on.
-- If such an instance is not found, returns nil.
---@param instance integer -- the 0-based index of the UART instance to return.
---@return AP_HAL__UARTDriver_ud|nil -- the requested UART instance available for scripting, or nil if none.
-- Returns a serial access object that allows a script to interface with a
-- device over a port set to protocol 28 (Scripting) (e.g. SERIALx_PROTOCOL).
-- Instance 0 is the first such port, instance 1 the second, and so on. If the
-- requested instance is not found, returns nil.
---@param instance integer -- 0-based index of the Scripting port to access
---@return AP_Scripting_SerialAccess_ud|nil -- access object for that instance, or nil if not found
function serial:find_serial(instance) end

View File

@ -392,18 +392,19 @@ singleton RC_Channels method lua_rc_channel RC_Channel uint8_t 1 NUM_RC_CHANNELS
singleton RC_Channels method lua_rc_channel rename get_channel
singleton RC_Channels method get_aux_cached boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX uint8_t'Null
include AP_SerialManager/AP_SerialManager.h
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 read int16_t
userdata AP_Scripting_SerialAccess manual readstring AP_Scripting_SerialAccess_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
ap_object AP_HAL::UARTDriver method begin void uint32_t 1U UINT32_MAX
ap_object AP_HAL::UARTDriver method read int16_t
ap_object AP_HAL::UARTDriver manual readstring AP_HAL__UARTDriver_readstring 1 1
ap_object AP_HAL::UARTDriver method write uint32_t uint8_t'skip_check
ap_object AP_HAL::UARTDriver method available uint32_t
ap_object AP_HAL::UARTDriver method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_RTS_DE
singleton AP_SerialManager rename serial
singleton AP_SerialManager depends HAL_GCS_ENABLED
singleton AP_SerialManager method find_serial AP_HAL::UARTDriver AP_SerialManager::SerialProtocol_Scripting'literal uint8_t'skip_check
-- serial is not a real C++ type here, but its name never gets used in C++ as we only have manual methods
singleton serial depends HAL_GCS_ENABLED
singleton serial manual find_serial lua_serial_find_serial 1 1
include AP_Baro/AP_Baro.h
singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO))

View File

@ -655,10 +655,10 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L) {
return success;
}
int AP_HAL__UARTDriver_readstring(lua_State *L) {
int AP_Scripting_SerialAccess_readstring(lua_State *L) {
binding_argcheck(L, 2);
AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1);
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);
@ -666,7 +666,7 @@ int AP_HAL__UARTDriver_readstring(lua_State *L) {
return 0;
}
const auto ret = ud->read(data, count);
const auto ret = p->read(data, count);
if (ret < 0) {
free(data);
return 0;
@ -743,6 +743,30 @@ int lua_get_CAN_device2(lua_State *L) {
}
#endif // AP_SCRIPTING_CAN_SENSOR_ENABLED
#if HAL_GCS_ENABLED
int lua_serial_find_serial(lua_State *L) {
// Allow : and . access
const int arg_offset = (luaL_testudata(L, 1, "serial") != NULL) ? 1 : 0;
binding_argcheck(L, 1 + arg_offset);
uint8_t instance = get_uint8_t(L, 1 + arg_offset);
AP_SerialManager *mgr = &AP::serialmanager();
AP_HAL::UARTDriver *driver_stream = mgr->find_serial(
AP_SerialManager::SerialProtocol_Scripting, instance);
if (driver_stream == nullptr) { // not found
return 0;
}
new_AP_Scripting_SerialAccess(L);
check_AP_Scripting_SerialAccess(L, -1)->stream = driver_stream;
return 1;
}
#endif // HAL_GCS_ENABLED
/*
directory listing, return table of files in a directory
*/

View File

@ -8,9 +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_HAL__UARTDriver_readstring(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_dirlist(lua_State *L);
int lua_removefile(lua_State *L);
int SRV_Channels_get_safety_state(lua_State *L);