diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index ea5e4f42a6b0e1..ccc60ab0dfecf2 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -6,7 +6,6 @@ #include "AP_Networking_ChibiOS.h" #include -#include #include #include diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index 1eb886d77c6210..c1f8ecaa76065b 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -12,6 +12,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -32,7 +33,7 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 auto &driver = *(AP_Networking_PPP *)ctx; LWIP_UNUSED_ARG(pcb); uint32_t remaining = len; - uint8_t *ptr = const_cast((const uint8_t *)data); + const uint8_t *ptr = (const uint8_t *)data; while (remaining > 0) { auto n = driver.uart->write(ptr, remaining); if (n > 0) { @@ -122,7 +123,8 @@ void AP_Networking_PPP::ppp_status_callback(struct ppp_pcb_s *pcb, int code, voi */ bool AP_Networking_PPP::init() { - uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_PPP, 0); + auto &sm = AP::serialmanager(); + uart = sm.find_serial(AP_SerialManager::SerialProtocol_PPP, 0); if (uart == nullptr) { return false; } diff --git a/libraries/AP_Networking/config/lwipopts.h b/libraries/AP_Networking/config/lwipopts.h index a2a516e91349fd..5c65b49f88fb56 100644 --- a/libraries/AP_Networking/config/lwipopts.h +++ b/libraries/AP_Networking/config/lwipopts.h @@ -88,6 +88,9 @@ extern "C" #define LWIP_TIMEVAL_PRIVATE 0 #define LWIP_FD_SET_PRIVATE 0 +#define TCP_WND 12000 +#define TCP_SND_BUF 12000 + // #define LWIP_DEBUG #ifdef LWIP_DEBUG #define LWIP_DBG_MIN_LEVEL 0 @@ -204,7 +207,9 @@ a lot of data that needs to be copied, this should be set high. */ #define TCP_MSS 1024 /* TCP sender buffer space (bytes). */ +#ifndef TCP_SND_BUF #define TCP_SND_BUF 2048 +#endif /* TCP sender buffer space (pbufs). This must be at least = 2 * TCP_SND_BUF/TCP_MSS for things to work. */ @@ -216,7 +221,9 @@ a lot of data that needs to be copied, this should be set high. */ #define TCP_SNDLOWAT (TCP_SND_BUF/2) /* TCP receive window. */ +#ifndef TCP_WND #define TCP_WND (20 * 1024) +#endif /* Maximum number of retransmissions of data segments. */ #define TCP_MAXRTX 12