AP_Networking: speed up sendfile download

use a multiple of sector size and DMA safe memory
This commit is contained in:
Andrew Tridgell 2024-01-05 13:37:02 +11:00 committed by Tom Pittenger
parent c5f295e852
commit b0bbed01c6
3 changed files with 12 additions and 3 deletions

View File

@ -293,7 +293,15 @@ bool AP_Networking::sendfile(SocketAPM *sock, int fd)
{
WITH_SEMAPHORE(sem);
if (sendfile_buf == nullptr) {
sendfile_buf = (uint8_t *)malloc(AP_NETWORKING_SENDFILE_BUFSIZE);
uint32_t bufsize = AP_NETWORKING_SENDFILE_BUFSIZE;
do {
sendfile_buf = (uint8_t *)hal.util->malloc_type(bufsize, AP_HAL::Util::MEM_FILESYSTEM);
if (sendfile_buf != nullptr) {
sendfile_bufsize = bufsize;
break;
}
bufsize /= 2;
} while (bufsize >= 4096);
if (sendfile_buf == nullptr) {
return false;
}
@ -344,7 +352,7 @@ void AP_Networking::sendfile_check(void)
if (!s.sock->pollout(0)) {
continue;
}
const auto nread = AP::FS().read(s.fd, sendfile_buf, AP_NETWORKING_SENDFILE_BUFSIZE);
const auto nread = AP::FS().read(s.fd, sendfile_buf, sendfile_bufsize);
if (nread <= 0) {
s.close();
continue;

View File

@ -278,6 +278,7 @@ private:
} sendfiles[AP_NETWORKING_NUM_SENDFILES];
uint8_t *sendfile_buf;
uint32_t sendfile_bufsize;
void sendfile_check(void);
bool sendfile_thread_started;

View File

@ -117,5 +117,5 @@
#endif
#ifndef AP_NETWORKING_SENDFILE_BUFSIZE
#define AP_NETWORKING_SENDFILE_BUFSIZE 10000
#define AP_NETWORKING_SENDFILE_BUFSIZE (64*512)
#endif