AP_Networking: added sendfile()

this allows for scripting to offload a file send to the AP_Networking
library, reducing CPU costs of large file downloads
This commit is contained in:
Andrew Tridgell 2023-12-08 05:32:32 +11:00
parent 9358bfce34
commit 241323eade
3 changed files with 100 additions and 0 deletions

View File

@ -8,6 +8,7 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_Math/crc.h>
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Filesystem/AP_Filesystem.h>
extern const AP_HAL::HAL& hal;
@ -19,6 +20,8 @@ extern const AP_HAL::HAL& hal;
#include <arpa/inet.h>
#endif
#include <AP_HAL/utility/Socket.h>
#if AP_NETWORKING_BACKEND_SITL
#include "AP_Networking_SITL.h"
#endif
@ -150,6 +153,9 @@ void AP_Networking::init()
// init network mapped serialmanager ports
ports_init();
// register sendfile handler
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Networking::sendfile_check, void));
}
/*
@ -282,6 +288,77 @@ void AP_Networking::startup_wait(void) const
#endif
}
/*
send the rest of a file to a socket
*/
bool AP_Networking::sendfile(SocketAPM *sock, int fd)
{
WITH_SEMAPHORE(sem);
if (sendfile_buf == nullptr) {
sendfile_buf = (uint8_t *)malloc(AP_NETWORKING_SENDFILE_BUFSIZE);
if (sendfile_buf == nullptr) {
return false;
}
}
for (auto &s : sendfiles) {
if (s.sock == nullptr) {
s.sock = sock->duplicate();
if (s.sock == nullptr) {
return false;
}
s.fd = fd;
return true;
}
}
return false;
}
void AP_Networking::SendFile::close(void)
{
AP::FS().close(fd);
delete sock;
sock = nullptr;
}
#include <stdio.h>
/*
check for sendfile updates
*/
void AP_Networking::sendfile_check(void)
{
if (sendfile_buf == nullptr) {
return;
}
WITH_SEMAPHORE(sem);
bool none_active = true;
for (auto &s : sendfiles) {
if (s.sock == nullptr) {
continue;
}
none_active = false;
if (!s.sock->pollout(0)) {
continue;
}
const auto nread = AP::FS().read(s.fd, sendfile_buf, AP_NETWORKING_SENDFILE_BUFSIZE);
if (nread <= 0) {
s.close();
continue;
}
const auto nsent = s.sock->send(sendfile_buf, nread);
if (nsent <= 0) {
s.close();
continue;
}
if (nsent < nread) {
AP::FS().lseek(s.fd, nsent - nread, SEEK_CUR);
}
}
if (none_active) {
free(sendfile_buf);
sendfile_buf = nullptr;
}
}
AP_Networking *AP_Networking::singleton;
namespace AP

View File

@ -188,6 +188,11 @@ public:
static uint32_t convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount);
static uint8_t convert_netmask_ip_to_bitcount(const uint32_t netmask_ip);
/*
send contents of a file to a socket then close both socket and file
*/
bool sendfile(SocketAPM *sock, int fd);
static const struct AP_Param::GroupInfo var_info[];
private:
@ -311,6 +316,16 @@ private:
// ports for registration with serial manager
Port ports[AP_NETWORKING_NUM_PORTS];
// support for sendfile()
struct SendFile {
SocketAPM *sock;
int fd;
void close(void);
} sendfiles[AP_NETWORKING_NUM_SENDFILES];
uint8_t *sendfile_buf;
void sendfile_check(void);
void ports_init(void);
};

View File

@ -89,3 +89,11 @@
#ifndef AP_NETWORKING_NUM_PORTS
#define AP_NETWORKING_NUM_PORTS 4
#endif
#ifndef AP_NETWORKING_NUM_SENDFILES
#define AP_NETWORKING_NUM_SENDFILES 20
#endif
#ifndef AP_NETWORKING_SENDFILE_BUFSIZE
#define AP_NETWORKING_SENDFILE_BUFSIZE 10000
#endif