From d289ba0181f82a8e91ec513d24ba90b9b613559f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:38:56 +1100 Subject: [PATCH] AP_Networking: removed SLIP PPP is the better choice --- libraries/AP_Networking/AP_Networking.cpp | 10 -- .../AP_Networking/AP_Networking_Config.h | 4 - .../AP_Networking/AP_Networking_SLIP.cpp | 98 ------------------- libraries/AP_Networking/AP_Networking_SLIP.h | 27 ----- 4 files changed, 139 deletions(-) delete mode 100644 libraries/AP_Networking/AP_Networking_SLIP.cpp delete mode 100644 libraries/AP_Networking/AP_Networking_SLIP.h diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 32bbf51de5..2eaee5dfde 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -24,10 +24,6 @@ extern const AP_HAL::HAL& hal; #include -#if AP_NETWORKING_BACKEND_SLIP -#include "AP_Networking_SLIP.h" -#endif - #if AP_NETWORKING_BACKEND_PPP #include "AP_Networking_PPP.h" #endif @@ -140,12 +136,6 @@ void AP_Networking::init() } #endif -#if AP_NETWORKING_BACKEND_SLIP - if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_SLIP, 0)) { - backend = new AP_Networking_SLIP(*this); - } -#endif - #if AP_NETWORKING_BACKEND_CHIBIOS if (backend == nullptr) { backend = new AP_Networking_ChibiOS(*this); diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index dcecd2be3a..b08b936e3b 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -31,10 +31,6 @@ #define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED) #endif -#ifndef AP_NETWORKING_BACKEND_SLIP -#define AP_NETWORKING_BACKEND_SLIP 0 -#endif - #ifndef AP_NETWORKING_BACKEND_SITL #define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #endif diff --git a/libraries/AP_Networking/AP_Networking_SLIP.cpp b/libraries/AP_Networking/AP_Networking_SLIP.cpp deleted file mode 100644 index b1e5085b5d..0000000000 --- a/libraries/AP_Networking/AP_Networking_SLIP.cpp +++ /dev/null @@ -1,98 +0,0 @@ - -#include "AP_Networking_Config.h" - -#if AP_NETWORKING_BACKEND_SLIP - -#include "AP_Networking_SLIP.h" -#include - -#include -#include -#include -#include - -#include - -extern const AP_HAL::HAL& hal; -AP_HAL::UARTDriver *AP_Networking_SLIP::uart; - -/* - initialise SLIP network backend using LWIP - */ -bool AP_Networking_SLIP::init() -{ - uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLIP, 0); - if (uart == nullptr) { - return false; - } - uart->set_unbuffered_writes(true); - - slipif = new netif; - if (slipif == nullptr) { - return false; - } - - // no dynamic IPs for SLIP - activeSettings.ip = frontend.get_ip_param(); - activeSettings.gw = frontend.get_gateway_param(); - activeSettings.nm = frontend.get_netmask_param(); - activeSettings.last_change_ms = AP_HAL::millis(); - - const ip4_addr_t ipaddr {htonl(activeSettings.ip)}; - const ip4_addr_t netmask {htonl(activeSettings.nm)}; - const ip4_addr_t gw {htonl(activeSettings.gw)}; - - tcpip_init(NULL, NULL); - hal.scheduler->delay(100); - - netif_add(slipif, - &ipaddr, &netmask, &gw, - &num_slip, slipif_init, ip_input); - netif_set_default(slipif); - slipif->mtu = 296; - netif_set_link_up(slipif); - netif_set_up(slipif); - - hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_SLIP::slip_loop, void), - "slip", - 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); - - return true; -} - -/* - main loop for SLIP - */ -void AP_Networking_SLIP::slip_loop(void) -{ - uart->begin(0); - hal.scheduler->delay(100); - while (true) { - slipif_poll(slipif); - hal.scheduler->delay_microseconds(100); - } -} - -void sio_send(uint8_t c, void *fd) -{ - auto *uart = (AP_HAL::UARTDriver *)fd; - uart->write(c); -} - -sio_fd_t sio_open(uint8_t dev) -{ - return AP_Networking_SLIP::uart; -} - -u32_t sio_tryread(sio_fd_t fd, u8_t *data, u32_t len) -{ - auto *uart = (AP_HAL::UARTDriver *)fd; - uart->begin(0); - const auto ret = uart->read(data, len); - if (ret <= 0) { - return 0; - } - return ret; -} - -#endif // AP_NETWORKING_BACKEND_SLIP diff --git a/libraries/AP_Networking/AP_Networking_SLIP.h b/libraries/AP_Networking/AP_Networking_SLIP.h deleted file mode 100644 index a6c61d4f32..0000000000 --- a/libraries/AP_Networking/AP_Networking_SLIP.h +++ /dev/null @@ -1,27 +0,0 @@ -#pragma once - -#include "AP_Networking_Config.h" - -#ifdef AP_NETWORKING_BACKEND_SLIP -#include "AP_Networking_Backend.h" - -class AP_Networking_SLIP : public AP_Networking_Backend -{ -public: - using AP_Networking_Backend::AP_Networking_Backend; - - /* Do not allow copies */ - CLASS_NO_COPY(AP_Networking_SLIP); - - bool init() override; - - static AP_HAL::UARTDriver *uart; - -private: - void slip_loop(void); - - struct netif *slipif; - uint8_t num_slip; -}; - -#endif // AP_NETWORKING_BACKEND_SLIP