mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: introduce serial device simulation support
Allows a script to simulate a device attached via any serial protocol. The script can read and write data and have it handled according to the protocol as if exchanged over a serial port. The script can then do protocol translation, data filtering and validation, hardware-in-the-loop simulation, experimentation, etc., especially in combination with the scripting protocol which lets the script itself handle an attached device and so interpose any communication.
This commit is contained in:
parent
4df2a1bce7
commit
a077e4a3ed
|
@ -161,6 +161,43 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = {
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("THD_PRIORITY", 14, AP_Scripting, _thd_priority, uint8_t(ThreadPriority::NORMAL)),
|
AP_GROUPINFO("THD_PRIORITY", 14, AP_Scripting, _thd_priority, uint8_t(ThreadPriority::NORMAL)),
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
// @Param: SDEV_EN
|
||||||
|
// @DisplayName: Scripting serial device enable
|
||||||
|
// @Description: Enable scripting serial devices
|
||||||
|
// @Values: 0:Disabled, 1:Enabled
|
||||||
|
// @RebootRequired: True
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO_FLAGS("SDEV_EN", 15, AP_Scripting, _serialdevice.enable, 0, AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
|
// @Param: SDEV1_PROTO
|
||||||
|
// @DisplayName: Serial protocol of scripting serial device
|
||||||
|
// @Description: Serial protocol of scripting serial device
|
||||||
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
|
// @RebootRequired: True
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("SDEV1_PROTO", 16, AP_Scripting, _serialdevice.ports[0].state.protocol, -1),
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_NUM_PORTS > 1
|
||||||
|
// @Param: SDEV2_PROTO
|
||||||
|
// @DisplayName: Serial protocol of scripting serial device
|
||||||
|
// @Description: Serial protocol of scripting serial device
|
||||||
|
// @CopyFieldsFrom: SCR_SDEV1_PROTO
|
||||||
|
AP_GROUPINFO("SDEV2_PROTO", 17, AP_Scripting, _serialdevice.ports[1].state.protocol, -1),
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_NUM_PORTS > 2
|
||||||
|
// @Param: SDEV3_PROTO
|
||||||
|
// @DisplayName: Serial protocol of scripting serial device
|
||||||
|
// @Description: Serial protocol of scripting serial device
|
||||||
|
// @CopyFieldsFrom: SCR_SDEV1_PROTO
|
||||||
|
AP_GROUPINFO("SDEV3_PROTO", 18, AP_Scripting, _serialdevice.ports[2].state.protocol, -1),
|
||||||
|
#endif
|
||||||
|
#endif // AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
|
||||||
|
// WARNING: additional parameters must be listed before SDEV_EN (but have an
|
||||||
|
// index after SDEV3_PROTO) so they are not disabled by it!
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -220,6 +257,16 @@ void AP_Scripting::init(void) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
void AP_Scripting::init_serialdevice_ports(void) {
|
||||||
|
if (!_enable) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
_serialdevice.init();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_GCS_ENABLED
|
#if HAL_GCS_ENABLED
|
||||||
MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t &packet) {
|
MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t &packet) {
|
||||||
switch ((SCRIPTING_CMD)packet.param1) {
|
switch ((SCRIPTING_CMD)packet.param1) {
|
||||||
|
|
|
@ -39,6 +39,14 @@
|
||||||
class SocketAPM;
|
class SocketAPM;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
#define AP_SCRIPTING_SERIALDEVICE_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
#include "AP_Scripting_SerialDevice.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
class AP_Scripting
|
class AP_Scripting
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -49,6 +57,10 @@ public:
|
||||||
|
|
||||||
void init(void);
|
void init(void);
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
void init_serialdevice_ports(void);
|
||||||
|
#endif
|
||||||
|
|
||||||
void update();
|
void update();
|
||||||
|
|
||||||
bool enabled(void) const { return _enable != 0; };
|
bool enabled(void) const { return _enable != 0; };
|
||||||
|
@ -138,6 +150,10 @@ public:
|
||||||
command_block_list *mavlink_command_block_list;
|
command_block_list *mavlink_command_block_list;
|
||||||
HAL_Semaphore mavlink_command_block_list_sem;
|
HAL_Semaphore mavlink_command_block_list_sem;
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
AP_Scripting_SerialDevice _serialdevice;
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void thread(void); // main script execution thread
|
void thread(void); // main script execution thread
|
||||||
|
|
|
@ -1,16 +1,28 @@
|
||||||
/*
|
/*
|
||||||
generic object to allow a script to use a serial stream
|
generic object to allow a script to use a serial driver stream from both
|
||||||
|
driver and device perspectives
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_Scripting_config.h"
|
#include "AP_Scripting_config.h"
|
||||||
|
#include "AP_Scripting.h"
|
||||||
#include "AP_Scripting_SerialAccess.h"
|
#include "AP_Scripting_SerialAccess.h"
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
#if AP_SCRIPTING_ENABLED
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
#define check_is_device_port() (is_device_port)
|
||||||
|
#define ON_DEVICE_PORT(func, ...) (((AP_Scripting_SerialDevice::Port*)stream)->device_##func (__VA_ARGS__))
|
||||||
|
#else
|
||||||
|
#define check_is_device_port() (false)
|
||||||
|
#define ON_DEVICE_PORT(...) (0) // not executed
|
||||||
|
#endif
|
||||||
|
|
||||||
void AP_Scripting_SerialAccess::begin(uint32_t baud)
|
void AP_Scripting_SerialAccess::begin(uint32_t baud)
|
||||||
{
|
{
|
||||||
|
if (!check_is_device_port()) {
|
||||||
stream->begin(baud);
|
stream->begin(baud);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
size_t AP_Scripting_SerialAccess::write(uint8_t c)
|
size_t AP_Scripting_SerialAccess::write(uint8_t c)
|
||||||
{
|
{
|
||||||
|
@ -19,8 +31,11 @@ size_t AP_Scripting_SerialAccess::write(uint8_t c)
|
||||||
|
|
||||||
size_t AP_Scripting_SerialAccess::write(const uint8_t *buffer, size_t size)
|
size_t AP_Scripting_SerialAccess::write(const uint8_t *buffer, size_t size)
|
||||||
{
|
{
|
||||||
|
if (!check_is_device_port()) {
|
||||||
return stream->write(buffer, size);
|
return stream->write(buffer, size);
|
||||||
}
|
}
|
||||||
|
return ON_DEVICE_PORT(write, buffer, size);
|
||||||
|
}
|
||||||
|
|
||||||
int16_t AP_Scripting_SerialAccess::read(void)
|
int16_t AP_Scripting_SerialAccess::read(void)
|
||||||
{
|
{
|
||||||
|
@ -33,17 +48,25 @@ int16_t AP_Scripting_SerialAccess::read(void)
|
||||||
|
|
||||||
ssize_t AP_Scripting_SerialAccess::read(uint8_t* buffer, uint16_t count)
|
ssize_t AP_Scripting_SerialAccess::read(uint8_t* buffer, uint16_t count)
|
||||||
{
|
{
|
||||||
|
if (!check_is_device_port()) {
|
||||||
return stream->read(buffer, count);
|
return stream->read(buffer, count);
|
||||||
}
|
}
|
||||||
|
return ON_DEVICE_PORT(read, buffer, count);
|
||||||
|
}
|
||||||
|
|
||||||
uint32_t AP_Scripting_SerialAccess::available(void)
|
uint32_t AP_Scripting_SerialAccess::available(void)
|
||||||
{
|
{
|
||||||
|
if (!check_is_device_port()) {
|
||||||
return stream->available();
|
return stream->available();
|
||||||
}
|
}
|
||||||
|
return ON_DEVICE_PORT(available);
|
||||||
|
}
|
||||||
|
|
||||||
void AP_Scripting_SerialAccess::set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs)
|
void AP_Scripting_SerialAccess::set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs)
|
||||||
{
|
{
|
||||||
|
if (!check_is_device_port()) {
|
||||||
stream->set_flow_control(fcs);
|
stream->set_flow_control(fcs);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
|
|
|
@ -1,5 +1,8 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Scripting_config.h"
|
||||||
|
#include "AP_Scripting.h"
|
||||||
|
|
||||||
#include <AP_HAL/UARTDriver.h>
|
#include <AP_HAL/UARTDriver.h>
|
||||||
|
|
||||||
class AP_Scripting_SerialAccess {
|
class AP_Scripting_SerialAccess {
|
||||||
|
@ -22,4 +25,9 @@ public:
|
||||||
void set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs);
|
void set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs);
|
||||||
|
|
||||||
AP_HAL::UARTDriver *stream;
|
AP_HAL::UARTDriver *stream;
|
||||||
|
#if AP_SCRIPTING_ENABLED
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
bool is_device_port;
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
|
@ -0,0 +1,142 @@
|
||||||
|
/*
|
||||||
|
port for a script to access from a device perspective
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "AP_Scripting_config.h"
|
||||||
|
#include "AP_Scripting.h"
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_ENABLED && AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
|
||||||
|
#ifndef AP_SCRIPTING_SERIALDEVICE_MIN_TXSIZE
|
||||||
|
#define AP_SCRIPTING_SERIALDEVICE_MIN_TXSIZE 2048
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_SCRIPTING_SERIALDEVICE_MIN_RXSIZE
|
||||||
|
#define AP_SCRIPTING_SERIALDEVICE_MIN_RXSIZE 2048
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
initialise scripting serial ports
|
||||||
|
*/
|
||||||
|
void AP_Scripting_SerialDevice::init(void)
|
||||||
|
{
|
||||||
|
if (enable == 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (uint8_t i=0; i<ARRAY_SIZE(ports); i++) {
|
||||||
|
auto &p = ports[i];
|
||||||
|
p.state.idx = AP_SERIALMANAGER_SCR_PORT_1 + i;
|
||||||
|
p.init();
|
||||||
|
AP::serialmanager().register_port(&p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
initialise port
|
||||||
|
*/
|
||||||
|
void AP_Scripting_SerialDevice::Port::init(void)
|
||||||
|
{
|
||||||
|
begin(1000000, 0, 0); // assume 1MBaud rate even though it's a bit meaningless
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t AP_Scripting_SerialDevice::Port::device_write(const uint8_t *buffer, size_t size)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
if (readbuffer) {
|
||||||
|
return readbuffer->write(buffer, size);
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t AP_Scripting_SerialDevice::Port::device_read(uint8_t *buffer, uint16_t count)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
if (writebuffer) {
|
||||||
|
return writebuffer->read(buffer, count);
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t AP_Scripting_SerialDevice::Port::device_available(void)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
if (writebuffer) {
|
||||||
|
return writebuffer->available();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
available space in outgoing buffer
|
||||||
|
*/
|
||||||
|
uint32_t AP_Scripting_SerialDevice::Port::txspace(void)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
return writebuffer != nullptr ? writebuffer->space() : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void AP_Scripting_SerialDevice::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||||
|
{
|
||||||
|
rxS = MAX(rxS, AP_SCRIPTING_SERIALDEVICE_MIN_RXSIZE);
|
||||||
|
txS = MAX(txS, AP_SCRIPTING_SERIALDEVICE_MIN_TXSIZE);
|
||||||
|
init_buffers(rxS, txS);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t AP_Scripting_SerialDevice::Port::_write(const uint8_t *buffer, size_t size)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
return writebuffer != nullptr ? writebuffer->write(buffer, size) : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t AP_Scripting_SerialDevice::Port::_read(uint8_t *buffer, uint16_t count)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
return readbuffer != nullptr ? readbuffer->read(buffer, count) : -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t AP_Scripting_SerialDevice::Port::_available()
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
return readbuffer != nullptr ? readbuffer->available() : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool AP_Scripting_SerialDevice::Port::_discard_input()
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
if (readbuffer != nullptr) {
|
||||||
|
readbuffer->clear();
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
initialise read/write buffers
|
||||||
|
*/
|
||||||
|
bool AP_Scripting_SerialDevice::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx)
|
||||||
|
{
|
||||||
|
if (size_tx == last_size_tx &&
|
||||||
|
size_rx == last_size_rx) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
if (readbuffer == nullptr) {
|
||||||
|
readbuffer = NEW_NOTHROW ByteBuffer(size_rx);
|
||||||
|
} else {
|
||||||
|
readbuffer->set_size_best(size_rx);
|
||||||
|
}
|
||||||
|
if (writebuffer == nullptr) {
|
||||||
|
writebuffer = NEW_NOTHROW ByteBuffer(size_tx);
|
||||||
|
} else {
|
||||||
|
writebuffer->set_size_best(size_tx);
|
||||||
|
}
|
||||||
|
last_size_rx = size_rx;
|
||||||
|
last_size_tx = size_tx;
|
||||||
|
return readbuffer != nullptr && writebuffer != nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // AP_SCRIPTING_ENABLED && AP_SCRIPTING_SERIALDEVICE_ENABLED
|
|
@ -0,0 +1,61 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
|
||||||
|
#ifndef AP_SCRIPTING_SERIALDEVICE_NUM_PORTS
|
||||||
|
#define AP_SCRIPTING_SERIALDEVICE_NUM_PORTS 3
|
||||||
|
#endif
|
||||||
|
|
||||||
|
class AP_Scripting;
|
||||||
|
|
||||||
|
class AP_Scripting_SerialDevice
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
/* Do not allow copies */
|
||||||
|
CLASS_NO_COPY(AP_Scripting_SerialDevice);
|
||||||
|
|
||||||
|
AP_Scripting_SerialDevice() {}
|
||||||
|
|
||||||
|
AP_Int8 enable;
|
||||||
|
|
||||||
|
void init(void);
|
||||||
|
|
||||||
|
public:
|
||||||
|
class Port : public AP_SerialManager::RegisteredPort {
|
||||||
|
public:
|
||||||
|
friend class AP_Scripting_SerialDevice;
|
||||||
|
void init(void);
|
||||||
|
|
||||||
|
size_t device_write(const uint8_t *buffer, size_t size);
|
||||||
|
ssize_t device_read(uint8_t *buffer, uint16_t count);
|
||||||
|
uint32_t device_available(void);
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool is_initialized() override {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
bool tx_pending() override {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool init_buffers(const uint32_t size_rx, const uint32_t size_tx);
|
||||||
|
|
||||||
|
uint32_t txspace() override;
|
||||||
|
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
|
||||||
|
size_t _write(const uint8_t *buffer, size_t size) override;
|
||||||
|
ssize_t _read(uint8_t *buffer, uint16_t count) override;
|
||||||
|
uint32_t _available() override;
|
||||||
|
void _end() override {}
|
||||||
|
void _flush() override {}
|
||||||
|
bool _discard_input() override;
|
||||||
|
|
||||||
|
ByteBuffer *readbuffer;
|
||||||
|
ByteBuffer *writebuffer;
|
||||||
|
uint32_t last_size_tx;
|
||||||
|
uint32_t last_size_rx;
|
||||||
|
|
||||||
|
HAL_Semaphore sem;
|
||||||
|
};
|
||||||
|
|
||||||
|
Port ports[AP_SCRIPTING_SERIALDEVICE_NUM_PORTS];
|
||||||
|
};
|
|
@ -1233,7 +1233,7 @@ function AP_HAL__I2CDevice_ud:set_retries(retries) end
|
||||||
---@class (exact) AP_Scripting_SerialAccess_ud
|
---@class (exact) AP_Scripting_SerialAccess_ud
|
||||||
local AP_Scripting_SerialAccess_ud = {}
|
local AP_Scripting_SerialAccess_ud = {}
|
||||||
|
|
||||||
-- Start serial port with the given baud rate
|
-- Start serial port with the given baud rate (no effect for device ports)
|
||||||
---@param baud_rate uint32_t_ud|integer|number
|
---@param baud_rate uint32_t_ud|integer|number
|
||||||
function AP_Scripting_SerialAccess_ud:begin(baud_rate) end
|
function AP_Scripting_SerialAccess_ud:begin(baud_rate) end
|
||||||
|
|
||||||
|
@ -1263,7 +1263,7 @@ function AP_Scripting_SerialAccess_ud:readstring(count) end
|
||||||
---@return uint32_t_ud
|
---@return uint32_t_ud
|
||||||
function AP_Scripting_SerialAccess_ud:available() end
|
function AP_Scripting_SerialAccess_ud:available() end
|
||||||
|
|
||||||
-- Set flow control option for serial port
|
-- Set flow control option for serial port (no effect for device ports)
|
||||||
---@param flow_control_setting integer
|
---@param flow_control_setting integer
|
||||||
---| '0' # disabled
|
---| '0' # disabled
|
||||||
---| '1' # enabled
|
---| '1' # enabled
|
||||||
|
@ -2119,6 +2119,16 @@ serial = {}
|
||||||
---@return AP_Scripting_SerialAccess_ud|nil -- access object for that instance, or nil if not found
|
---@return AP_Scripting_SerialAccess_ud|nil -- access object for that instance, or nil if not found
|
||||||
function serial:find_serial(instance) end
|
function serial:find_serial(instance) end
|
||||||
|
|
||||||
|
-- Returns a serial access object that allows a script to simulate a device
|
||||||
|
-- attached via a specific protocol. The device protocol is configured by
|
||||||
|
-- SCR_SDEVx_PROTO. Instance 0 is the first such protocol, instance 1 the
|
||||||
|
-- second, and so on. If the requested instance is not found, or SCR_SDEV_EN is
|
||||||
|
-- disabled, returns nil.
|
||||||
|
---@param protocol integer -- protocol to access
|
||||||
|
---@param instance integer -- 0-based index of the protocol instance to access
|
||||||
|
---@return AP_Scripting_SerialAccess_ud|nil -- access object for that instance, or nil if not found
|
||||||
|
function serial:find_simulated_device(protocol, instance) end
|
||||||
|
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
rc = {}
|
rc = {}
|
||||||
|
|
|
@ -406,6 +406,7 @@ userdata AP_Scripting_SerialAccess method set_flow_control void AP_HAL::UARTDriv
|
||||||
-- serial is not a real C++ type here, but its name never gets used in C++ as we only have manual methods
|
-- 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 depends HAL_GCS_ENABLED
|
||||||
singleton serial manual find_serial lua_serial_find_serial 1 1
|
singleton serial manual find_serial lua_serial_find_serial 1 1
|
||||||
|
singleton serial manual find_simulated_device lua_serial_find_simulated_device 2 1 depends AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
|
||||||
include AP_Baro/AP_Baro.h
|
include AP_Baro/AP_Baro.h
|
||||||
singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO))
|
singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO))
|
||||||
|
|
|
@ -737,12 +737,52 @@ int lua_serial_find_serial(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
new_AP_Scripting_SerialAccess(L);
|
new_AP_Scripting_SerialAccess(L);
|
||||||
check_AP_Scripting_SerialAccess(L, -1)->stream = driver_stream;
|
AP_Scripting_SerialAccess *port = check_AP_Scripting_SerialAccess(L, -1);
|
||||||
|
port->stream = driver_stream;
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
port->is_device_port = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
#endif // HAL_GCS_ENABLED
|
#endif // HAL_GCS_ENABLED
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
int lua_serial_find_simulated_device(lua_State *L) {
|
||||||
|
// Allow : and . access
|
||||||
|
const int arg_offset = (luaL_testudata(L, 1, "serial") != NULL) ? 1 : 0;
|
||||||
|
|
||||||
|
binding_argcheck(L, 2 + arg_offset);
|
||||||
|
|
||||||
|
const int8_t protocol = (int8_t)get_uint32(L, 1 + arg_offset, 0, 127);
|
||||||
|
uint32_t instance = get_uint16_t(L, 2 + arg_offset);
|
||||||
|
|
||||||
|
auto *scripting = AP::scripting();
|
||||||
|
AP_Scripting_SerialDevice::Port *device_stream = nullptr;
|
||||||
|
|
||||||
|
for (auto &port : scripting->_serialdevice.ports) {
|
||||||
|
if (port.state.protocol == protocol) {
|
||||||
|
if (instance-- == 0) {
|
||||||
|
device_stream = &port;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!scripting->_serialdevice.enable || device_stream == nullptr) {
|
||||||
|
// serial devices as a whole are disabled, or port not found
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
new_AP_Scripting_SerialAccess(L);
|
||||||
|
AP_Scripting_SerialAccess *port = check_AP_Scripting_SerialAccess(L, -1);
|
||||||
|
port->stream = device_stream;
|
||||||
|
port->is_device_port = true;
|
||||||
|
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
#endif // AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||||
|
|
||||||
int lua_serial_writestring(lua_State *L)
|
int lua_serial_writestring(lua_State *L)
|
||||||
{
|
{
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
|
|
@ -11,6 +11,7 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L);
|
||||||
int lua_get_CAN_device(lua_State *L);
|
int lua_get_CAN_device(lua_State *L);
|
||||||
int lua_get_CAN_device2(lua_State *L);
|
int lua_get_CAN_device2(lua_State *L);
|
||||||
int lua_serial_find_serial(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_writestring(lua_State *L);
|
||||||
int lua_serial_readstring(lua_State *L);
|
int lua_serial_readstring(lua_State *L);
|
||||||
int lua_dirlist(lua_State *L);
|
int lua_dirlist(lua_State *L);
|
||||||
|
|
Loading…
Reference in New Issue