Skip to content

Commit

Permalink
AP_Networking: fup
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Dec 25, 2023
1 parent 37c7747 commit 3fa0fa4
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 3 deletions.
1 change: 0 additions & 1 deletion libraries/AP_Networking/AP_Networking_ChibiOS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include "AP_Networking_ChibiOS.h"
#include <GCS_MAVLink/GCS.h>

#include <lwipthread.h>
#include <lwip/udp.h>
#include <lwip/ip_addr.h>

Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_Networking/AP_Networking_PPP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#include <netif/ppp/pppapi.h>
#include <netif/ppp/pppos.h>
#include <lwip/tcpip.h>
#include <stdio.h>


extern const AP_HAL::HAL& hal;
Expand All @@ -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<uint8_t*>((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) {
Expand Down Expand Up @@ -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;
}
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_Networking/config/lwipopts.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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. */
Expand All @@ -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
Expand Down

0 comments on commit 3fa0fa4

Please sign in to comment.