Skip to content

Commit

Permalink
AP_Scripting: added bindings for SocketAPM
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Dec 4, 2023
1 parent 6d09664 commit 423c8fd
Show file tree
Hide file tree
Showing 7 changed files with 351 additions and 0 deletions.
15 changes: 15 additions & 0 deletions libraries/AP_Scripting/AP_Scripting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,10 @@ static_assert(SCRIPTING_STACK_SIZE <= SCRIPTING_STACK_MAX_SIZE, "Scripting requi
#define SCRIPTING_ENABLE_DEFAULT 0
#endif

#if AP_NETWORKING_ENABLED
#include <AP_HAL/utility/Socket.h>
#endif

extern const AP_HAL::HAL& hal;

const AP_Param::GroupInfo AP_Scripting::var_info[] = {
Expand Down Expand Up @@ -270,6 +274,17 @@ void AP_Scripting::thread(void) {
}
num_pwm_source = 0;

#if AP_NETWORKING_ENABLED
// clear allocated sockets
for (uint8_t i=0; i<SCRIPTING_MAX_NUM_NET_SOCKET; i++) {
if (_net_sockets[i] != nullptr) {
delete _net_sockets[i];
_net_sockets[i] = nullptr;
}
}
num_net_sockets = 0;
#endif // AP_NETWORKING_ENABLED

// Clear blocked commands
{
WITH_SEMAPHORE(mavlink_command_block_list_sem);
Expand Down
14 changes: 14 additions & 0 deletions libraries/AP_Scripting/AP_Scripting.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,21 @@
#include <AP_Filesystem/AP_Filesystem.h>
#include <AP_HAL/I2CDevice.h>
#include "AP_Scripting_CANSensor.h"
#include <AP_Networking/AP_Networking_Config.h>

#ifndef SCRIPTING_MAX_NUM_I2C_DEVICE
#define SCRIPTING_MAX_NUM_I2C_DEVICE 4
#endif

#define SCRIPTING_MAX_NUM_PWM_SOURCE 4

#if AP_NETWORKING_ENABLED
#ifndef SCRIPTING_MAX_NUM_NET_SOCKET
#define SCRIPTING_MAX_NUM_NET_SOCKET 10
#endif
class SocketAPM;
#endif

class AP_Scripting
{
public:
Expand Down Expand Up @@ -109,6 +117,12 @@ class AP_Scripting
int get_current_ref() { return current_ref; }
void set_current_ref(int ref) { current_ref = ref; }

#if AP_NETWORKING_ENABLED
// SocketAPM storage
uint8_t num_net_sockets;
SocketAPM *_net_sockets[SCRIPTING_MAX_NUM_NET_SOCKET];
#endif

struct mavlink_msg {
mavlink_message_t msg;
mavlink_channel_t chan;
Expand Down
45 changes: 45 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -452,6 +452,51 @@ function motor_factor_table_ud:roll(index) end
---@param value number
function motor_factor_table_ud:roll(index, value) end

-- network socket class
---@class SocketAPM_ud
local SocketAPM_ud = {}

-- desc
---@return boolean
function SocketAPM_ud:is_connected() end

-- desc
---@param param1 boolean
---@return boolean
function SocketAPM_ud:set_blocking(param1) end

-- desc
---@param param1 integer
---@return boolean
function SocketAPM_ud:listen(param1) end

-- desc
---@param param1 string
---@param param2 uint32_t_ud
---@return integer
function SocketAPM_ud:send(param1, param2) end

-- desc
---@param param1 string
---@param param2 integer
---@return boolean
function SocketAPM_ud:bind(param1, param2) end

-- desc
---@param param1 string
---@param param2 integer
---@return boolean
function SocketAPM_ud:connect(param1, param2) end

-- desc
function SocketAPM_ud:__gc() end

-- desc
function SocketAPM_ud:accept(param1) end

-- desc
function SocketAPM_ud:recv(param1) end


-- desc
---@class AP_HAL__PWMSource_ud
Expand Down
140 changes: 140 additions & 0 deletions libraries/AP_Scripting/examples/net_test.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
--[[
example script to test lua socket API
--]]

local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

PARAM_TABLE_KEY = 46
PARAM_TABLE_PREFIX = "NT_"

-- bind a parameter to a variable given
function bind_param(name)
local p = Parameter()
assert(p:init(name), string.format('could not find %s parameter', name))
return p
end

-- add a parameter and bind it to a variable
function bind_add_param(name, idx, default_value)
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
return bind_param(PARAM_TABLE_PREFIX .. name)
end

-- Setup Parameters
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'net_test: could not add param table')

--[[
// @Param: NT_ENABLE
// @DisplayName: enable network tests
// @Description: Enable network tests
// @Values: 0:Disabled,1:Enabled
// @User: Standard
--]]
local NT_ENABLE = bind_add_param('ENABLE', 1, 0)
if NT_ENABLE:get() == 0 then
return
end

local NT_TEST_IP = { bind_add_param('TEST_IP0', 2, 192),
bind_add_param('TEST_IP1', 3, 168),
bind_add_param('TEST_IP2', 4, 13),
bind_add_param('TEST_IP3', 5, 15) }

local NT_BIND_PORT = bind_add_param('BIND_PORT', 6, 15001)

local PORT_ECHO = 7

gcs:send_text(MAV_SEVERITY.INFO, "net_test: starting")

local function test_ip()
return string.format("%u.%u.%u.%u", NT_TEST_IP[1]:get(), NT_TEST_IP[2]:get(), NT_TEST_IP[3]:get(), NT_TEST_IP[4]:get())
end

local counter = 0
local sock_tcp_echo = SocketAPM(0)
local sock_udp_echo = SocketAPM(1)
local sock_tcp_in = SocketAPM(0)
local sock_tcp_in2 = nil
local sock_udp_in = SocketAPM(1)

if not sock_tcp_echo then
gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to create tcp echo socket")
return
end

if not sock_udp_echo then
gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to create udp echo socket")
return
end

if not sock_tcp_in:bind("0.0.0.0", NT_BIND_PORT:get()) then
gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to bind to TCP 5001")
end

if not sock_tcp_in:listen(1) then
gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to listen")
end

if not sock_udp_in:bind("0.0.0.0", NT_BIND_PORT:get()) then
gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to bind to UDP 5001")
end

--[[
test TCP or UDP echo
--]]
local function test_echo(name, sock)
if not sock:is_connected() then
if not sock:connect(test_ip(), PORT_ECHO) then
gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): failed to connect", name))
return
end

if not sock:set_blocking(true) then
gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): failed to set blocking", name))
return
end
end

local s = string.format("testing %u", counter)
local nsent = sock:send(s, #s)
if nsent ~= #s then
gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): failed to send", name))
return
end
local r = sock:recv(#s)
if r then
gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): got reply '%s'", name, r))
end
end

--[[
test a simple server
--]]
local function test_server(name, sock)
if name == "TCP" then
if not sock_tcp_in2 then
sock_tcp_in2 = sock:accept()
if not sock_tcp_in2 then
return
end
gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_server(%s): new connection", name))
end
sock = sock_tcp_in2
end

local r = sock:recv(1024)
if r and #r > 0 then
gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_server(%s): got input '%s'", name, r))
end
end

local function update()
test_echo("TCP", sock_tcp_echo)
test_echo("UDP", sock_udp_echo)
test_server("TCP", sock_tcp_in)
test_server("UDP", sock_udp_in)
counter = counter + 1
return update,1000
end

return update,100
13 changes: 13 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -536,6 +536,19 @@ ap_object AP_HAL::I2CDevice method write_register boolean uint8_t'skip_check uin
ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers 2
ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check

include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1)
global manual SocketAPM lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1)

ap_object SocketAPM depends (AP_NETWORKING_ENABLED==1)
ap_object SocketAPM method connect boolean string uint16_t'skip_check
ap_object SocketAPM method bind boolean string uint16_t'skip_check
ap_object SocketAPM method send int32_t string uint32_t'skip_check
ap_object SocketAPM method listen boolean uint8_t'skip_check
ap_object SocketAPM method set_blocking boolean boolean
ap_object SocketAPM method is_connected boolean
ap_object SocketAPM manual close SocketAPM_close 0
ap_object SocketAPM manual recv SocketAPM_recv 1
ap_object SocketAPM manual accept SocketAPM_accept 1

ap_object AP_HAL::AnalogSource depends !defined(HAL_DISABLE_ADC_DRIVER)
ap_object AP_HAL::AnalogSource method set_pin boolean uint8_t'skip_check
Expand Down
Loading

0 comments on commit 423c8fd

Please sign in to comment.