AP_Networking: removed SLIP

PPP is the better choice
This commit is contained in:
Andrew Tridgell 2023-12-26 06:38:56 +11:00
parent 22938e99ea
commit d289ba0181
4 changed files with 0 additions and 139 deletions

View File

@ -24,10 +24,6 @@ extern const AP_HAL::HAL& hal;
#include <AP_HAL/utility/Socket.h> #include <AP_HAL/utility/Socket.h>
#if AP_NETWORKING_BACKEND_SLIP
#include "AP_Networking_SLIP.h"
#endif
#if AP_NETWORKING_BACKEND_PPP #if AP_NETWORKING_BACKEND_PPP
#include "AP_Networking_PPP.h" #include "AP_Networking_PPP.h"
#endif #endif
@ -140,12 +136,6 @@ void AP_Networking::init()
} }
#endif #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 AP_NETWORKING_BACKEND_CHIBIOS
if (backend == nullptr) { if (backend == nullptr) {
backend = new AP_Networking_ChibiOS(*this); backend = new AP_Networking_ChibiOS(*this);

View File

@ -31,10 +31,6 @@
#define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED) #define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED)
#endif #endif
#ifndef AP_NETWORKING_BACKEND_SLIP
#define AP_NETWORKING_BACKEND_SLIP 0
#endif
#ifndef AP_NETWORKING_BACKEND_SITL #ifndef AP_NETWORKING_BACKEND_SITL
#define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL))
#endif #endif

View File

@ -1,98 +0,0 @@
#include "AP_Networking_Config.h"
#if AP_NETWORKING_BACKEND_SLIP
#include "AP_Networking_SLIP.h"
#include <GCS_MAVLink/GCS.h>
#include <lwip/udp.h>
#include <lwip/ip_addr.h>
#include <lwip/sio.h>
#include <lwip/tcpip.h>
#include <netif/slipif.h>
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

View File

@ -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