mirror of https://github.com/ArduPilot/ardupilot
AP_Networking: added SLIP support
This commit is contained in:
parent
1627f7f61a
commit
e2dac53fca
|
@ -14,6 +14,7 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
#if AP_NETWORKING_BACKEND_CHIBIOS
|
||||
#include "AP_Networking_ChibiOS.h"
|
||||
#include "AP_Networking_SLIP.h"
|
||||
#include <hal_mii.h>
|
||||
#include <lwip/sockets.h>
|
||||
#else
|
||||
|
@ -22,6 +23,10 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#if AP_NETWORKING_BACKEND_SLIP
|
||||
#include "AP_Networking_SLIP.h"
|
||||
#endif
|
||||
|
||||
#if AP_NETWORKING_BACKEND_SITL
|
||||
#include "AP_Networking_SITL.h"
|
||||
#endif
|
||||
|
@ -124,11 +129,21 @@ void AP_Networking::init()
|
|||
}
|
||||
#endif
|
||||
|
||||
#if AP_NETWORKING_BACKEND_SLIP
|
||||
if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_SLIP, 0)) {
|
||||
backend = new AP_Networking_SLIP(*this);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_NETWORKING_BACKEND_CHIBIOS
|
||||
backend = new AP_Networking_ChibiOS(*this);
|
||||
if (backend == nullptr) {
|
||||
backend = new AP_Networking_ChibiOS(*this);
|
||||
}
|
||||
#endif
|
||||
#if AP_NETWORKING_BACKEND_SITL
|
||||
backend = new AP_Networking_SITL(*this);
|
||||
if (backend == nullptr) {
|
||||
backend = new AP_Networking_SITL(*this);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (backend == nullptr) {
|
||||
|
@ -374,15 +389,16 @@ AP_Networking &network()
|
|||
*/
|
||||
int ap_networking_printf(const char *fmt, ...)
|
||||
{
|
||||
#ifdef AP_NETWORKING_LWIP_DEBUG_PORT
|
||||
#if AP_NETWORKING_LWIP_DEBUG_PORT >= 0
|
||||
static AP_HAL::UARTDriver *uart;
|
||||
if (uart == nullptr) {
|
||||
uart = hal.serial(AP_NETWORKING_LWIP_DEBUG_PORT);
|
||||
if (uart == nullptr) {
|
||||
return -1;
|
||||
}
|
||||
uart->begin(921600, 0, 50000);
|
||||
uart->begin(AP_NETWORKING_LWIP_DEBUG_BAUD, 1000, 50000);
|
||||
}
|
||||
uart->begin(0);
|
||||
va_list ap;
|
||||
va_start(ap, fmt);
|
||||
uart->vprintf(fmt, ap);
|
||||
|
|
|
@ -19,7 +19,7 @@ public:
|
|||
CLASS_NO_COPY(AP_Networking_Backend);
|
||||
|
||||
virtual bool init() = 0;
|
||||
virtual void update() = 0;
|
||||
virtual void update() {};
|
||||
|
||||
protected:
|
||||
AP_Networking &frontend;
|
||||
|
|
|
@ -22,6 +22,11 @@
|
|||
// ---------------------------
|
||||
#ifndef AP_NETWORKING_BACKEND_CHIBIOS
|
||||
#define AP_NETWORKING_BACKEND_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS))
|
||||
#define AP_NETWORKING_BACKEND_SLIP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS))
|
||||
#endif
|
||||
|
||||
#ifndef AP_NETWORKING_BACKEND_SLIP
|
||||
#define AP_NETWORKING_BACKEND_SLIP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS))
|
||||
#endif
|
||||
|
||||
#ifndef AP_NETWORKING_BACKEND_SITL
|
||||
|
|
|
@ -16,7 +16,6 @@ public:
|
|||
bool init() override {
|
||||
return true;
|
||||
}
|
||||
void update() override {}
|
||||
};
|
||||
|
||||
#endif // AP_NETWORKING_BACKEND_SITL
|
||||
|
|
|
@ -0,0 +1,99 @@
|
|||
|
||||
#include "AP_Networking_Config.h"
|
||||
|
||||
#if AP_NETWORKING_BACKEND_SLIP
|
||||
|
||||
#include "AP_Networking_SLIP.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#include <lwipthread.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
|
|
@ -0,0 +1,27 @@
|
|||
#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
|
Loading…
Reference in New Issue