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: added socket network bindings #25687

Merged
merged 33 commits into from
Dec 11, 2023
Merged
Show file tree
Hide file tree
Changes from 30 commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
1b85565
AP_HAL: mark new accept() socket as connected
tridge Dec 3, 2023
2d97d64
AP_HAL: added close() to SocketAPM
tridge Dec 3, 2023
0a063bb
AP_HAL: fixed SO_REUSEADDR on bind
tridge Dec 4, 2023
33ec538
AP_HAL: mark socket as not connected on EOF
tridge Dec 5, 2023
998de91
AP_Filesystem: fixed fseek and open of directories
tridge Dec 4, 2023
e3562bf
AP_Filesystem: added option @SYS/flash.bin
tridge Dec 4, 2023
604f0a1
HAL_ChibiOS: defaults to 50 socket limit
tridge Dec 5, 2023
84bbdef
AP_Scripting: added bindings for SocketAPM
tridge Dec 3, 2023
b3750cd
AP_Scripting: added isdirectory()
tridge Dec 4, 2023
a2c280b
AP_Scripting: added web server appliction
tridge Dec 3, 2023
ed0856d
AP_Scripting: added poll bindings
tridge Dec 7, 2023
82e56cf
AP_Networking: make lwip debugging easier
tridge Dec 7, 2023
c490f26
HAL_ChibiOS: make lwip debugging easier
tridge Dec 7, 2023
cf35ec4
AP_Scripting: improve web server debug
tridge Dec 7, 2023
3d9a144
waf: fix dependency on lwip code
tridge Dec 7, 2023
de03aff
HAL_ChibiOS: adjust buffer sizes
tridge Dec 7, 2023
8b9c310
HAL_ChibiOS: increase LWIP windows
tridge Dec 8, 2023
220a1b4
AP_Scripting: webserver improvements
tridge Dec 7, 2023
b178b9a
AP_Filesystem: expose APFS_FILE structure
tridge Dec 7, 2023
6de3817
AP_HAL: added duplicate() in SocketAPM
tridge Dec 7, 2023
5d28424
AP_Networking: added sendfile()
tridge Dec 7, 2023
8178d11
AP_Scripting: added sendfile() API on sockets
tridge Dec 7, 2023
0f6c1e2
AP_Scripting: use sendfile() in web server
tridge Dec 7, 2023
3cde84f
AP_Filesystem: implement stat() call for lua
tridge Dec 8, 2023
646423c
AP_RTC: added time and date APIs for lua
tridge Dec 8, 2023
1f362e0
AP_Scripting: added stat() binding for filesystem
tridge Dec 8, 2023
24bde34
AP_Scripting: added If-Modified-Since for webserver
tridge Dec 8, 2023
3893c50
AP_Scripting: added a home page and ajax support
tridge Dec 9, 2023
e2e61d8
AP_Scripting: updated docs
tridge Dec 9, 2023
648731c
AP_Scripting: fixed webserver warnings
tridge Dec 9, 2023
a1b27a2
AP_RTC: fixed build on arm
tridge Dec 10, 2023
cc4692d
AP_Scripting: review fixes
tridge Dec 10, 2023
5913b82
Tools: fixed AerobaticsScripting test
tridge Dec 10, 2023
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
2 changes: 2 additions & 0 deletions Tools/ardupilotwaf/chibios.py
Original file line number Diff line number Diff line change
Expand Up @@ -675,6 +675,8 @@ def build(bld):
common_src += bld.path.ant_glob('libraries/AP_HAL_ChibiOS/hwdef/common/*.mk')
common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.[ch]')
common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.mk')
common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/**/*.[ch]')
common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/core/**/*.[ch]')
if bld.env.ROMFS_FILES:
common_src += [bld.bldnode.find_or_declare('ap_romfs_embedded.h')]

Expand Down
24 changes: 24 additions & 0 deletions libraries/AP_Filesystem/AP_Filesystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -333,6 +333,30 @@ AP_Filesystem_Backend::FormatStatus AP_Filesystem::get_format_status(void) const
}
#endif

/*
stat wrapper for scripting
*/
bool AP_Filesystem::stat(const char *pathname, stat_t &stbuf)
{
struct stat st;
if (fs.stat(pathname, &st) != 0) {
return false;
}
stbuf.size = st.st_size;
Copy link
Contributor

Choose a reason for hiding this comment

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

memset

stbuf.mode = st.st_mode;
// these wrap in 2038
stbuf.atime = st.st_atime;
stbuf.ctime = st.st_ctime;
stbuf.mtime = st.st_mtime;
return true;
}

// get_singleton for scripting
AP_Filesystem *AP_Filesystem::get_singleton(void)
{
return &fs;
}

namespace AP
{
AP_Filesystem &FS()
Expand Down
19 changes: 18 additions & 1 deletion libraries/AP_Filesystem/AP_Filesystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,20 @@ class AP_Filesystem {
int fsync(int fd);
int32_t lseek(int fd, int32_t offset, int whence);
int stat(const char *pathname, struct stat *stbuf);

// stat variant for scripting
typedef struct {
uint32_t size;
int32_t mode;
uint32_t mtime;
uint32_t atime;
uint32_t ctime;
bool is_directory(void) const {
return (mode & S_IFMT) == S_IFDIR;
}
} stat_t;
bool stat(const char *pathname, stat_t &stbuf);

int unlink(const char *pathname);
int mkdir(const char *pathname);
int rename(const char *oldpath, const char *newpath);
Expand Down Expand Up @@ -121,7 +135,10 @@ class AP_Filesystem {
load a full file. Use delete to free the data
*/
FileData *load_file(const char *filename);


// get_singleton for scripting
static AP_Filesystem *get_singleton(void);

private:
struct Backend {
const char *prefix;
Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_Filesystem/AP_Filesystem_Sys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ static const SysFileList sysfs_file_list[] = {
#endif
{"crash_dump.bin"},
{"storage.bin"},
#if AP_FILESYSTEM_SYS_FLASH_ENABLED
{"flash.bin"},
#endif
};

int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) {
Expand Down Expand Up @@ -152,6 +155,13 @@ int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_pa
r.str->set_buffer((char*)ptr, size, size);
}
}
#if AP_FILESYSTEM_SYS_FLASH_ENABLED
if (strcmp(fname, "flash.bin") == 0) {
void *ptr = (void*)0x08000000;
const size_t size = BOARD_FLASH_SIZE*1024;
r.str->set_buffer((char*)ptr, size, size);
}
#endif

if (r.str->get_length() == 0) {
errno = r.str->has_failed_allocation()?ENOMEM:ENOENT;
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Filesystem/AP_Filesystem_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,3 +50,6 @@
#define AP_FILESYSTEM_FILE_READING_ENABLED (AP_FILESYSTEM_FILE_WRITING_ENABLED || AP_FILESYSTEM_ROMFS_ENABLED)
#endif

#ifndef AP_FILESYSTEM_SYS_FLASH_ENABLED
#define AP_FILESYSTEM_SYS_FLASH_ENABLED CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#endif
6 changes: 6 additions & 0 deletions libraries/AP_Filesystem/AP_Filesystem_posix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,12 @@ int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_
if (! allow_absolute_paths) {
fname = map_filename(fname);
}
struct stat st;
if (::stat(fname, &st) == 0 &&
((st.st_mode & S_IFMT) != S_IFREG && (st.st_mode & S_IFMT) != S_IFLNK)) {
// only allow links and files
return -1;
}
// we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage
return ::open(fname, flags | O_CLOEXEC, 0644);
}
Expand Down
11 changes: 2 additions & 9 deletions libraries/AP_Filesystem/posix_compat.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,14 +30,6 @@
#include <stdarg.h>
#include <AP_Math/AP_Math.h>

struct apfs_file {
int fd;
bool error;
bool eof;
int16_t unget;
char *tmpfile_name;
};

#define CHECK_STREAM(stream, ret) while (stream == NULL || stream->fd < 0) { errno = EBADF; return ret; }

#define modecmp(str, pat) (strcmp(str, pat) == 0 ? 1: 0)
Expand Down Expand Up @@ -170,7 +162,8 @@ int apfs_fseek(APFS_FILE *stream, long offset, int whence)
{
CHECK_STREAM(stream, EOF);
stream->eof = false;
return AP::FS().lseek(stream->fd, offset, whence);
AP::FS().lseek(stream->fd, offset, whence);
return 0;
}

int apfs_ferror(APFS_FILE *stream)
Expand Down
9 changes: 8 additions & 1 deletion libraries/AP_Filesystem/posix_compat.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <sys/types.h>
#include <stdio.h>
#include <stddef.h>
#include <stdbool.h>

#ifdef __cplusplus
extern "C" {
Expand All @@ -29,7 +30,13 @@ extern "C" {
these are here to allow lua to build on HAL_ChibiOS
*/

typedef struct apfs_file APFS_FILE;
typedef struct apfs_file {
int fd;
bool error;
bool eof;
int16_t unget;
char *tmpfile_name;
} APFS_FILE;

APFS_FILE *apfs_fopen(const char *pathname, const char *mode);
int apfs_fprintf(APFS_FILE *stream, const char *format, ...);
Expand Down
91 changes: 81 additions & 10 deletions libraries/AP_HAL/utility/Socket.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,7 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) :

SocketAPM::~SocketAPM()
{
if (fd != -1) {
CALL_PREFIX(close)(fd);
fd = -1;
}
if (fd_in != -1) {
CALL_PREFIX(close)(fd_in);
fd_in = -1;
}
close();
}

void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr)
Expand All @@ -79,6 +72,9 @@ void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockadd
*/
bool SocketAPM::connect(const char *address, uint16_t port)
{
if (fd == -1) {
return false;
}
struct sockaddr_in sockaddr;
int ret;
int one = 1;
Expand Down Expand Up @@ -163,6 +159,9 @@ bool SocketAPM::connect(const char *address, uint16_t port)
*/
bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms)
{
if (fd == -1) {
return false;
}
struct sockaddr_in sockaddr;
make_sockaddr(address, port, sockaddr);

Expand Down Expand Up @@ -194,9 +193,13 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim
*/
bool SocketAPM::bind(const char *address, uint16_t port)
{
if (fd == -1) {
return false;
}
struct sockaddr_in sockaddr;
make_sockaddr(address, port, sockaddr);

reuseaddress();
if (CALL_PREFIX(bind)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) {
return false;
}
Expand All @@ -209,6 +212,9 @@ bool SocketAPM::bind(const char *address, uint16_t port)
*/
bool SocketAPM::reuseaddress(void) const
{
if (fd == -1) {
return false;
}
int one = 1;
return (CALL_PREFIX(setsockopt)(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1);
}
Expand All @@ -218,6 +224,9 @@ bool SocketAPM::reuseaddress(void) const
*/
bool SocketAPM::set_blocking(bool blocking) const
{
if (fd == -1) {
return false;
}
int fcntl_ret;
if (blocking) {
fcntl_ret = CALL_PREFIX(fcntl)(fd, F_SETFL, CALL_PREFIX(fcntl)(fd, F_GETFL, 0) & ~O_NONBLOCK);
Expand All @@ -238,6 +247,9 @@ bool SocketAPM::set_blocking(bool blocking) const
*/
bool SocketAPM::set_cloexec() const
{
if (fd == -1) {
return false;
}
#ifdef FD_CLOEXEC
return (CALL_PREFIX(fcntl)(fd, F_SETFD, FD_CLOEXEC) != -1);
#else
Expand All @@ -250,14 +262,20 @@ bool SocketAPM::set_cloexec() const
*/
ssize_t SocketAPM::send(const void *buf, size_t size) const
{
return CALL_PREFIX(send)(fd, buf, size, 0);
if (fd == -1) {
return -1;
}
return CALL_PREFIX(send)(fd, buf, size, MSG_NOSIGNAL);
}

/*
send some data
*/
ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uint16_t port)
{
if (fd == -1) {
return -1;
}
struct sockaddr_in sockaddr;
make_sockaddr(address, port, sockaddr);
return CALL_PREFIX(sendto)(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
Expand All @@ -277,6 +295,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
ssize_t ret;
ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len);
if (ret <= 0) {
if (!datagram && connected && ret == 0) {
// remote host has closed connection
connected = false;
}
return ret;
}
if (fd_in != -1) {
Expand Down Expand Up @@ -322,6 +344,9 @@ const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint

void SocketAPM::set_broadcast(void) const
{
if (fd == -1) {
return;
}
int one = 1;
CALL_PREFIX(setsockopt)(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one));
}
Expand All @@ -336,6 +361,9 @@ bool SocketAPM::pollin(uint32_t timeout_ms)

FD_ZERO(&fds);
int fin = get_read_fd();
if (fin == -1) {
return false;
}
FD_SET(fin, &fds);

tv.tv_sec = timeout_ms / 1000;
Expand All @@ -353,6 +381,9 @@ bool SocketAPM::pollin(uint32_t timeout_ms)
*/
bool SocketAPM::pollout(uint32_t timeout_ms)
{
if (fd == -1) {
return false;
}
fd_set fds;
struct timeval tv;

Expand All @@ -373,6 +404,9 @@ bool SocketAPM::pollout(uint32_t timeout_ms)
*/
bool SocketAPM::listen(uint16_t backlog) const
{
if (fd == -1) {
return false;
}
return CALL_PREFIX(listen)(fd, (int)backlog) == 0;
}

Expand All @@ -382,6 +416,9 @@ bool SocketAPM::listen(uint16_t backlog) const
*/
SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
{
if (fd == -1) {
return nullptr;
}
if (!pollin(timeout_ms)) {
return nullptr;
}
Expand All @@ -391,7 +428,12 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
if (newfd == -1) {
return nullptr;
}
return new SocketAPM(false, newfd);
auto *ret = new SocketAPM(false, newfd);
if (ret != nullptr) {
ret->connected = true;
ret->reuseaddress();
}
return ret;
}

/*
Expand All @@ -405,4 +447,33 @@ bool SocketAPM::is_multicast_address(struct sockaddr_in &addr) const
return haddr >= mc_lower && haddr <= mc_upper;
}

void SocketAPM::close(void)
{
if (fd != -1) {
CALL_PREFIX(close)(fd);
fd = -1;
}
if (fd_in != -1) {
CALL_PREFIX(close)(fd_in);
fd_in = -1;
}
}

/*
duplicate a socket, giving a new object with the same contents,
the fd in the old object is set to -1
*/
SocketAPM *SocketAPM::duplicate(void)
{
auto *ret = new SocketAPM(datagram, fd);
if (ret == nullptr) {
return nullptr;
}
ret->fd_in = fd_in;
ret->connected = connected;
fd = -1;
fd_in = -1;
return ret;
}

#endif // AP_NETWORKING_BACKEND_ANY
7 changes: 7 additions & 0 deletions libraries/AP_HAL/utility/Socket.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,9 @@ class SocketAPM {
// start listening for new tcp connections
bool listen(uint16_t backlog) const;

// close socket
void close(void);

// accept a new connection. Only valid for TCP connections after
// listen has been used. A new socket is returned
SocketAPM *accept(uint32_t timeout_ms);
Expand All @@ -78,6 +81,10 @@ class SocketAPM {
return fd_in != -1? fd_in : fd;
}

// create a new socket with same fd, but new memory
// the old socket gets fd of -1
SocketAPM *duplicate(void);

bool is_connected(void) const {
return connected;
}
Expand Down
Loading
Loading