diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 87ca70bd94ad7..87b5147b75f24 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -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; diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 3b18072593b70..63936f025b2c5 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -278,6 +278,7 @@ class AP_Networking } sendfiles[AP_NETWORKING_NUM_SENDFILES]; uint8_t *sendfile_buf; + uint32_t sendfile_bufsize; void sendfile_check(void); bool sendfile_thread_started; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b9fdbd6fd3fb2..2fbf9d70b15c5 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -117,5 +117,5 @@ #endif #ifndef AP_NETWORKING_SENDFILE_BUFSIZE -#define AP_NETWORKING_SENDFILE_BUFSIZE 10000 +#define AP_NETWORKING_SENDFILE_BUFSIZE (64*512) #endif