mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Networking: added ArduPilot HAL port of lwip
This commit is contained in:
parent
b28912c351
commit
22938e99ea
@ -6,9 +6,16 @@
|
|||||||
#include "AP_Networking_ChibiOS.h"
|
#include "AP_Networking_ChibiOS.h"
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
#include <lwipthread.h>
|
|
||||||
#include <lwip/udp.h>
|
#include <lwip/udp.h>
|
||||||
#include <lwip/ip_addr.h>
|
#include <lwip/ip_addr.h>
|
||||||
|
#include <lwip/tcpip.h>
|
||||||
|
#include <lwip/netifapi.h>
|
||||||
|
#if LWIP_DHCP
|
||||||
|
#include <lwip/dhcp.h>
|
||||||
|
#endif
|
||||||
|
#include <hal.h>
|
||||||
|
#include "../../modules/ChibiOS/os/various/evtimer.h"
|
||||||
|
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -18,23 +25,34 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
/*
|
/*
|
||||||
these are referenced as globals inside lwip
|
these are referenced as globals inside lwip
|
||||||
*/
|
*/
|
||||||
stm32_eth_rx_descriptor_t *__eth_rd;
|
stm32_eth_rx_descriptor_t *__eth_rd;
|
||||||
stm32_eth_tx_descriptor_t *__eth_td;
|
stm32_eth_tx_descriptor_t *__eth_td;
|
||||||
uint32_t *__eth_rb[STM32_MAC_RECEIVE_BUFFERS];
|
uint32_t *__eth_rb[STM32_MAC_RECEIVE_BUFFERS];
|
||||||
uint32_t *__eth_tb[STM32_MAC_TRANSMIT_BUFFERS];
|
uint32_t *__eth_tb[STM32_MAC_TRANSMIT_BUFFERS];
|
||||||
|
|
||||||
|
#define LWIP_SEND_TIMEOUT_MS 50
|
||||||
|
#define LWIP_NETIF_MTU 1500
|
||||||
|
#define LWIP_LINK_POLL_INTERVAL TIME_S2I(5)
|
||||||
|
|
||||||
|
#define PERIODIC_TIMER_ID 1
|
||||||
|
#define FRAME_RECEIVED_ID 2
|
||||||
|
|
||||||
|
#if CH_CFG_ST_RESOLUTION != 32
|
||||||
|
#error "ethernet requires 32 bit timer"
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
allocate buffers for LWIP
|
allocate buffers for LWIP
|
||||||
*/
|
*/
|
||||||
bool AP_Networking_ChibiOS::allocate_buffers()
|
bool AP_Networking_ChibiOS::allocate_buffers()
|
||||||
{
|
{
|
||||||
#define AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE ((((STM32_MAC_BUFFERS_SIZE - 1) | 3) + 1) / 4) // typically == 381
|
#define AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE ((((STM32_MAC_BUFFERS_SIZE - 1) | 3) + 1) / 4) // typically == 381
|
||||||
// check total size of buffers
|
// check total size of buffers
|
||||||
const uint32_t total_size = sizeof(stm32_eth_rx_descriptor_t)*STM32_MAC_RECEIVE_BUFFERS +
|
const uint32_t total_size = sizeof(stm32_eth_rx_descriptor_t)*STM32_MAC_RECEIVE_BUFFERS +
|
||||||
sizeof(stm32_eth_tx_descriptor_t)*STM32_MAC_TRANSMIT_BUFFERS +
|
sizeof(stm32_eth_tx_descriptor_t)*STM32_MAC_TRANSMIT_BUFFERS +
|
||||||
sizeof(uint32_t)*STM32_MAC_RECEIVE_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE +
|
sizeof(uint32_t)*STM32_MAC_RECEIVE_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE +
|
||||||
sizeof(uint32_t)*STM32_MAC_TRANSMIT_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE; // typically == 9240
|
sizeof(uint32_t)*STM32_MAC_TRANSMIT_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE; // typically == 9240
|
||||||
|
|
||||||
// ensure that we allocate 32-bit aligned memory, and mark it non-cacheable
|
// ensure that we allocate 32-bit aligned memory, and mark it non-cacheable
|
||||||
uint32_t size = 1;
|
uint32_t size = 1;
|
||||||
@ -84,7 +102,7 @@ bool AP_Networking_ChibiOS::allocate_buffers()
|
|||||||
|
|
||||||
/*
|
/*
|
||||||
initialise ChibiOS network backend using LWIP
|
initialise ChibiOS network backend using LWIP
|
||||||
*/
|
*/
|
||||||
bool AP_Networking_ChibiOS::init()
|
bool AP_Networking_ChibiOS::init()
|
||||||
{
|
{
|
||||||
#ifdef HAL_GPIO_ETH_ENABLE
|
#ifdef HAL_GPIO_ETH_ENABLE
|
||||||
@ -102,21 +120,6 @@ bool AP_Networking_ChibiOS::init()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
lwip_options = new lwipthread_opts;
|
|
||||||
|
|
||||||
if (frontend.get_dhcp_enabled()) {
|
|
||||||
lwip_options->addrMode = NET_ADDRESS_DHCP;
|
|
||||||
} else {
|
|
||||||
lwip_options->addrMode = NET_ADDRESS_STATIC;
|
|
||||||
lwip_options->address = htonl(frontend.get_ip_param());
|
|
||||||
lwip_options->netmask = htonl(frontend.get_netmask_param());
|
|
||||||
lwip_options->gateway = htonl(frontend.get_gateway_param());
|
|
||||||
}
|
|
||||||
frontend.param.macaddr.get_address(macaddr);
|
|
||||||
lwip_options->macaddress = macaddr;
|
|
||||||
|
|
||||||
lwipInit(lwip_options);
|
|
||||||
|
|
||||||
#if LWIP_IGMP
|
#if LWIP_IGMP
|
||||||
if (ETH != nullptr) {
|
if (ETH != nullptr) {
|
||||||
// enbale "permit multicast" so we can receive multicast packets
|
// enbale "permit multicast" so we can receive multicast packets
|
||||||
@ -124,17 +127,252 @@ bool AP_Networking_ChibiOS::init()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
thisif = new netif;
|
||||||
|
if (thisif == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_ChibiOS::thread, void),
|
||||||
|
"network",
|
||||||
|
2048, AP_HAL::Scheduler::PRIORITY_NET, 0)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_Networking_ChibiOS::link_up_cb(void *p)
|
||||||
|
{
|
||||||
|
auto *driver = (AP_Networking_ChibiOS *)p;
|
||||||
|
#if LWIP_DHCP
|
||||||
|
if (driver->frontend.get_dhcp_enabled()) {
|
||||||
|
dhcp_start(driver->thisif);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void AP_Networking_ChibiOS::link_down_cb(void *p)
|
||||||
|
{
|
||||||
|
auto *driver = (AP_Networking_ChibiOS *)p;
|
||||||
|
#if LWIP_DHCP
|
||||||
|
if (driver->frontend.get_dhcp_enabled()) {
|
||||||
|
dhcp_stop(driver->thisif);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* This function does the actual transmission of the packet. The packet is
|
||||||
|
* contained in the pbuf that is passed to the function. This pbuf
|
||||||
|
* might be chained.
|
||||||
|
*
|
||||||
|
* @param netif the lwip network interface structure for this ethernetif
|
||||||
|
* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)
|
||||||
|
* @return ERR_OK if the packet could be sent
|
||||||
|
* an err_t value if the packet couldn't be sent
|
||||||
|
*
|
||||||
|
* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to
|
||||||
|
* strange results. You might consider waiting for space in the DMA queue
|
||||||
|
* to become available since the stack doesn't retry to send a packet
|
||||||
|
* dropped because of memory failure (except for the TCP timers).
|
||||||
|
*/
|
||||||
|
int8_t AP_Networking_ChibiOS::low_level_output(struct netif *netif, struct pbuf *p)
|
||||||
|
{
|
||||||
|
struct pbuf *q;
|
||||||
|
MACTransmitDescriptor td;
|
||||||
|
(void)netif;
|
||||||
|
|
||||||
|
if (macWaitTransmitDescriptor(ÐD1, &td, TIME_MS2I(LWIP_SEND_TIMEOUT_MS)) != MSG_OK) {
|
||||||
|
return ERR_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ETH_PAD_SIZE
|
||||||
|
pbuf_header(p, -ETH_PAD_SIZE); /* drop the padding word */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Iterates through the pbuf chain. */
|
||||||
|
for(q = p; q != NULL; q = q->next) {
|
||||||
|
macWriteTransmitDescriptor(&td, (uint8_t *)q->payload, (size_t)q->len);
|
||||||
|
}
|
||||||
|
macReleaseTransmitDescriptorX(&td);
|
||||||
|
|
||||||
|
#if ETH_PAD_SIZE
|
||||||
|
pbuf_header(p, ETH_PAD_SIZE); /* reclaim the padding word */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return ERR_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Receives a frame.
|
||||||
|
* Allocates a pbuf and transfers the bytes of the incoming
|
||||||
|
* packet from the interface into the pbuf.
|
||||||
|
*
|
||||||
|
* @param netif the lwip network interface structure for this ethernetif
|
||||||
|
* @return a pbuf filled with the received packet (including MAC header)
|
||||||
|
* NULL on memory error
|
||||||
|
*/
|
||||||
|
bool AP_Networking_ChibiOS::low_level_input(struct netif *netif, struct pbuf **pbuf)
|
||||||
|
{
|
||||||
|
MACReceiveDescriptor rd;
|
||||||
|
struct pbuf *q;
|
||||||
|
u16_t len;
|
||||||
|
|
||||||
|
(void)netif;
|
||||||
|
|
||||||
|
if (macWaitReceiveDescriptor(ÐD1, &rd, TIME_IMMEDIATE) != MSG_OK) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
len = (u16_t)rd.size;
|
||||||
|
|
||||||
|
#if ETH_PAD_SIZE
|
||||||
|
len += ETH_PAD_SIZE; /* allow room for Ethernet padding */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* We allocate a pbuf chain of pbufs from the pool. */
|
||||||
|
*pbuf = pbuf_alloc(PBUF_RAW, len, PBUF_POOL);
|
||||||
|
|
||||||
|
if (*pbuf != nullptr) {
|
||||||
|
#if ETH_PAD_SIZE
|
||||||
|
pbuf_header(*pbuf, -ETH_PAD_SIZE); /* drop the padding word */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Iterates through the pbuf chain. */
|
||||||
|
for(q = *pbuf; q != NULL; q = q->next) {
|
||||||
|
macReadReceiveDescriptor(&rd, (uint8_t *)q->payload, (size_t)q->len);
|
||||||
|
}
|
||||||
|
macReleaseReceiveDescriptorX(&rd);
|
||||||
|
|
||||||
|
#if ETH_PAD_SIZE
|
||||||
|
pbuf_header(*pbuf, ETH_PAD_SIZE); /* reclaim the padding word */
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
macReleaseReceiveDescriptorX(&rd); // Drop packet
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
int8_t AP_Networking_ChibiOS::ethernetif_init(struct netif *netif)
|
||||||
|
{
|
||||||
|
netif->state = NULL;
|
||||||
|
netif->name[0] = 'm';
|
||||||
|
netif->name[1] = 's';
|
||||||
|
netif->output = etharp_output;
|
||||||
|
netif->linkoutput = low_level_output;
|
||||||
|
|
||||||
|
/* set MAC hardware address length */
|
||||||
|
netif->hwaddr_len = ETHARP_HWADDR_LEN;
|
||||||
|
|
||||||
|
/* maximum transfer unit */
|
||||||
|
netif->mtu = LWIP_NETIF_MTU;
|
||||||
|
|
||||||
|
/* device capabilities */
|
||||||
|
netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP;
|
||||||
|
|
||||||
|
#if LWIP_IGMP
|
||||||
|
// also enable multicast
|
||||||
|
netif->flags |= NETIF_FLAG_IGMP;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return ERR_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
networking thread
|
||||||
|
*/
|
||||||
|
void AP_Networking_ChibiOS::thread()
|
||||||
|
{
|
||||||
|
while (!hal.scheduler->is_system_initialized()) {
|
||||||
|
hal.scheduler->delay_microseconds(1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* start tcpip thread */
|
||||||
|
tcpip_init(NULL, NULL);
|
||||||
|
|
||||||
|
frontend.param.macaddr.get_address(thisif->hwaddr);
|
||||||
|
|
||||||
|
struct {
|
||||||
|
ip4_addr_t ip, gateway, netmask;
|
||||||
|
} addr {};
|
||||||
|
|
||||||
|
if (!frontend.get_dhcp_enabled()) {
|
||||||
|
addr.ip.addr = htonl(frontend.get_ip_param());
|
||||||
|
addr.gateway.addr = htonl(frontend.get_gateway_param());
|
||||||
|
addr.netmask.addr = htonl(frontend.get_netmask_param());
|
||||||
|
}
|
||||||
|
|
||||||
|
const MACConfig mac_config = {thisif->hwaddr};
|
||||||
|
macStart(ÐD1, &mac_config);
|
||||||
|
|
||||||
|
/* Add interface. */
|
||||||
|
auto result = netifapi_netif_add(thisif, &addr.ip, &addr.netmask, &addr.gateway, NULL, ethernetif_init, tcpip_input);
|
||||||
|
if (result != ERR_OK) {
|
||||||
|
AP_HAL::panic("Failed to initialise netif");
|
||||||
|
}
|
||||||
|
|
||||||
|
netifapi_netif_set_default(thisif);
|
||||||
|
netifapi_netif_set_up(thisif);
|
||||||
|
|
||||||
|
/* Setup event sources.*/
|
||||||
|
event_timer_t evt;
|
||||||
|
event_listener_t el0, el1;
|
||||||
|
|
||||||
|
evtObjectInit(&evt, LWIP_LINK_POLL_INTERVAL);
|
||||||
|
evtStart(&evt);
|
||||||
|
chEvtRegisterMask(&evt.et_es, &el0, PERIODIC_TIMER_ID);
|
||||||
|
chEvtRegisterMaskWithFlags(macGetEventSource(ÐD1), &el1,
|
||||||
|
FRAME_RECEIVED_ID, MAC_FLAGS_RX);
|
||||||
|
chEvtAddEvents(PERIODIC_TIMER_ID | FRAME_RECEIVED_ID);
|
||||||
|
|
||||||
|
while (true) {
|
||||||
|
eventmask_t mask = chEvtWaitAny(ALL_EVENTS);
|
||||||
|
if (mask & PERIODIC_TIMER_ID) {
|
||||||
|
bool current_link_status = macPollLinkStatus(ÐD1);
|
||||||
|
if (current_link_status != netif_is_link_up(thisif)) {
|
||||||
|
if (current_link_status) {
|
||||||
|
tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_up, thisif, 0);
|
||||||
|
tcpip_callback_with_block(link_up_cb, this, 0);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_down, thisif, 0);
|
||||||
|
tcpip_callback_with_block(link_down_cb, this, 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mask & FRAME_RECEIVED_ID) {
|
||||||
|
struct pbuf *p;
|
||||||
|
while (low_level_input(thisif, &p)) {
|
||||||
|
if (p != NULL) {
|
||||||
|
struct eth_hdr *ethhdr = (struct eth_hdr *)p->payload;
|
||||||
|
switch (htons(ethhdr->type)) {
|
||||||
|
/* IP or ARP packet? */
|
||||||
|
case ETHTYPE_IP:
|
||||||
|
case ETHTYPE_ARP:
|
||||||
|
/* full packet send to tcpip_thread to process */
|
||||||
|
if (thisif->input(p, thisif) == ERR_OK) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
/* Falls through */
|
||||||
|
default:
|
||||||
|
pbuf_free(p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
update called at 10Hz
|
update called at 10Hz
|
||||||
*/
|
*/
|
||||||
void AP_Networking_ChibiOS::update()
|
void AP_Networking_ChibiOS::update()
|
||||||
{
|
{
|
||||||
const uint32_t ip = ntohl(lwipGetIp());
|
const uint32_t ip = ntohl(thisif->ip_addr.addr);
|
||||||
const uint32_t nm = ntohl(lwipGetNetmask());
|
const uint32_t nm = ntohl(thisif->netmask.addr);
|
||||||
const uint32_t gw = ntohl(lwipGetGateway());
|
const uint32_t gw = ntohl(thisif->gw.addr);
|
||||||
|
|
||||||
if (ip != activeSettings.ip ||
|
if (ip != activeSettings.ip ||
|
||||||
nm != activeSettings.nm ||
|
nm != activeSettings.nm ||
|
||||||
|
@ -18,10 +18,17 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
bool allocate_buffers(void);
|
bool allocate_buffers(void);
|
||||||
|
void thread(void);
|
||||||
|
static void link_up_cb(void*);
|
||||||
|
static void link_down_cb(void*);
|
||||||
|
static int8_t ethernetif_init(struct netif *netif);
|
||||||
|
static int8_t low_level_output(struct netif *netif, struct pbuf *p);
|
||||||
|
static bool low_level_input(struct netif *netif, struct pbuf **pbuf);
|
||||||
|
|
||||||
private:
|
|
||||||
struct lwipthread_opts *lwip_options;
|
struct lwipthread_opts *lwip_options;
|
||||||
uint8_t macaddr[6];
|
uint8_t macaddr[6];
|
||||||
|
|
||||||
|
struct netif *thisif;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_NETWORKING_BACKEND_CHIBIOS
|
#endif // AP_NETWORKING_BACKEND_CHIBIOS
|
||||||
|
@ -12,20 +12,11 @@
|
|||||||
#include <netif/ppp/pppapi.h>
|
#include <netif/ppp/pppapi.h>
|
||||||
#include <netif/ppp/pppos.h>
|
#include <netif/ppp/pppos.h>
|
||||||
#include <lwip/tcpip.h>
|
#include <lwip/tcpip.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
||||||
/*
|
|
||||||
uint32_t timestamp in smallest available units
|
|
||||||
*/
|
|
||||||
uint32_t sys_jiffies(void)
|
|
||||||
{
|
|
||||||
return AP_HAL::micros();
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if LWIP_TCPIP_CORE_LOCKING
|
#if LWIP_TCPIP_CORE_LOCKING
|
||||||
#define LWIP_TCPIP_LOCK() sys_lock_tcpip_core()
|
#define LWIP_TCPIP_LOCK() sys_lock_tcpip_core()
|
||||||
#define LWIP_TCPIP_UNLOCK() sys_unlock_tcpip_core()
|
#define LWIP_TCPIP_UNLOCK() sys_unlock_tcpip_core()
|
||||||
@ -42,7 +33,7 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32
|
|||||||
auto &driver = *(AP_Networking_PPP *)ctx;
|
auto &driver = *(AP_Networking_PPP *)ctx;
|
||||||
LWIP_UNUSED_ARG(pcb);
|
LWIP_UNUSED_ARG(pcb);
|
||||||
uint32_t remaining = len;
|
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) {
|
while (remaining > 0) {
|
||||||
auto n = driver.uart->write(ptr, remaining);
|
auto n = driver.uart->write(ptr, remaining);
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
@ -132,12 +123,12 @@ void AP_Networking_PPP::ppp_status_callback(struct ppp_pcb_s *pcb, int code, voi
|
|||||||
*/
|
*/
|
||||||
bool AP_Networking_PPP::init()
|
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) {
|
if (uart == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
uart->set_unbuffered_writes(true);
|
|
||||||
|
|
||||||
pppif = new netif;
|
pppif = new netif;
|
||||||
if (pppif == nullptr) {
|
if (pppif == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
@ -163,7 +154,7 @@ bool AP_Networking_PPP::init()
|
|||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: started");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: started");
|
||||||
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_PPP::ppp_loop, void),
|
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_PPP::ppp_loop, void),
|
||||||
"ppp",
|
"ppp",
|
||||||
2048, AP_HAL::Scheduler::PRIORITY_UART, 0);
|
2048, AP_HAL::Scheduler::PRIORITY_NET, 0);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -186,6 +177,7 @@ void AP_Networking_PPP::ppp_loop(void)
|
|||||||
|
|
||||||
// ensure this thread owns the uart
|
// ensure this thread owns the uart
|
||||||
uart->begin(0);
|
uart->begin(0);
|
||||||
|
uart->set_unbuffered_writes(true);
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
uint8_t buf[1024];
|
uint8_t buf[1024];
|
||||||
@ -194,9 +186,8 @@ void AP_Networking_PPP::ppp_loop(void)
|
|||||||
LWIP_TCPIP_LOCK();
|
LWIP_TCPIP_LOCK();
|
||||||
pppos_input(ppp, buf, n);
|
pppos_input(ppp, buf, n);
|
||||||
LWIP_TCPIP_UNLOCK();
|
LWIP_TCPIP_UNLOCK();
|
||||||
hal.scheduler->delay_microseconds(100);
|
|
||||||
} else {
|
} else {
|
||||||
hal.scheduler->delay_microseconds(1000);
|
hal.scheduler->delay_microseconds(200);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
365
libraries/AP_Networking/config/lwipopts.h
Normal file
365
libraries/AP_Networking/config/lwipopts.h
Normal file
@ -0,0 +1,365 @@
|
|||||||
|
/*
|
||||||
|
* Copyright (c) 2001-2003 Swedish Institute of Computer Science.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without modification,
|
||||||
|
* are permitted provided that the following conditions are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer in the documentation
|
||||||
|
* and/or other materials provided with the distribution.
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
|
||||||
|
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
|
||||||
|
* SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
|
||||||
|
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
|
||||||
|
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||||
|
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||||
|
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
|
||||||
|
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
|
||||||
|
* OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
* This file is part of the lwIP TCP/IP stack.
|
||||||
|
*
|
||||||
|
* Author: Adam Dunkels <adam@sics.se>
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef LWIP_OPTTEST_FILE
|
||||||
|
#include "lwipopts_test.h"
|
||||||
|
#else /* LWIP_OPTTEST_FILE */
|
||||||
|
|
||||||
|
#define LWIP_IPV4 1
|
||||||
|
#define LWIP_IPV6 0
|
||||||
|
|
||||||
|
#define MEM_LIBC_MALLOC 1
|
||||||
|
#define MEMP_MEM_MALLOC 1
|
||||||
|
#define LWIP_NETCONN_SEM_PER_THREAD 0
|
||||||
|
|
||||||
|
|
||||||
|
#define NO_SYS 0
|
||||||
|
#define LWIP_SOCKET (NO_SYS==0)
|
||||||
|
#define LWIP_NETCONN (NO_SYS==0)
|
||||||
|
#define LWIP_NETIF_API (NO_SYS==0)
|
||||||
|
|
||||||
|
#define LWIP_IGMP LWIP_IPV4
|
||||||
|
#define LWIP_ICMP LWIP_IPV4
|
||||||
|
|
||||||
|
#define LWIP_SNMP LWIP_UDP
|
||||||
|
#define MIB2_STATS LWIP_SNMP
|
||||||
|
#ifdef LWIP_HAVE_MBEDTLS
|
||||||
|
#define LWIP_SNMP_V3 (LWIP_SNMP)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define LWIP_DNS LWIP_UDP
|
||||||
|
#define LWIP_MDNS_RESPONDER LWIP_UDP
|
||||||
|
|
||||||
|
#define LWIP_NUM_NETIF_CLIENT_DATA (LWIP_MDNS_RESPONDER)
|
||||||
|
|
||||||
|
#define LWIP_HAVE_LOOPIF 1
|
||||||
|
#define LWIP_NETIF_LOOPBACK 1
|
||||||
|
#define LWIP_LOOPBACK_MAX_PBUFS 10
|
||||||
|
|
||||||
|
#define TCP_LISTEN_BACKLOG 1
|
||||||
|
|
||||||
|
#define LWIP_COMPAT_SOCKETS 0
|
||||||
|
#define LWIP_SO_RCVTIMEO 1
|
||||||
|
#define LWIP_SO_RCVBUF 1
|
||||||
|
|
||||||
|
#define LWIP_TCPIP_CORE_LOCKING 1
|
||||||
|
|
||||||
|
#define LWIP_NETIF_LINK_CALLBACK 1
|
||||||
|
#define LWIP_NETIF_STATUS_CALLBACK 1
|
||||||
|
#define LWIP_NETIF_EXT_STATUS_CALLBACK 1
|
||||||
|
|
||||||
|
#define USE_PPP 1
|
||||||
|
|
||||||
|
#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
|
||||||
|
#define PPP_DEBUG LWIP_DBG_ON
|
||||||
|
#define MEM_DEBUG LWIP_DBG_ON
|
||||||
|
#define MEMP_DEBUG LWIP_DBG_ON
|
||||||
|
#define PBUF_DEBUG LWIP_DBG_OFF
|
||||||
|
#define API_LIB_DEBUG LWIP_DBG_OFF
|
||||||
|
#define API_MSG_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCPIP_DEBUG LWIP_DBG_ON
|
||||||
|
#define NETIF_DEBUG LWIP_DBG_ON
|
||||||
|
#define SOCKETS_DEBUG LWIP_DBG_OFF
|
||||||
|
#define DNS_DEBUG LWIP_DBG_OFF
|
||||||
|
#define AUTOIP_DEBUG LWIP_DBG_OFF
|
||||||
|
#define DHCP_DEBUG LWIP_DBG_OFF
|
||||||
|
#define IP_DEBUG LWIP_DBG_OFF
|
||||||
|
#define IP_REASS_DEBUG LWIP_DBG_OFF
|
||||||
|
#define ICMP_DEBUG LWIP_DBG_OFF
|
||||||
|
#define IGMP_DEBUG LWIP_DBG_OFF
|
||||||
|
#define UDP_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCP_DEBUG LWIP_DBG_ON
|
||||||
|
#define TCP_INPUT_DEBUG LWIP_DBG_ON
|
||||||
|
#define TCP_OUTPUT_DEBUG LWIP_DBG_ON
|
||||||
|
#define TCP_RTO_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCP_CWND_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCP_WND_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCP_FR_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCP_QLEN_DEBUG LWIP_DBG_OFF
|
||||||
|
#define TCP_RST_DEBUG LWIP_DBG_OFF
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define LWIP_DBG_TYPES_ON (LWIP_DBG_ON|LWIP_DBG_TRACE|LWIP_DBG_STATE|LWIP_DBG_FRESH|LWIP_DBG_HALT)
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- Memory options ---------- */
|
||||||
|
/* MEM_ALIGNMENT: should be set to the alignment of the CPU for which
|
||||||
|
lwIP is compiled. 4 byte alignment -> define MEM_ALIGNMENT to 4, 2
|
||||||
|
byte alignment -> define MEM_ALIGNMENT to 2. */
|
||||||
|
/* MSVC port: intel processors don't need 4-byte alignment,
|
||||||
|
but are faster that way! */
|
||||||
|
#define MEM_ALIGNMENT 4U
|
||||||
|
|
||||||
|
/* MEM_SIZE: the size of the heap memory. If the application will send
|
||||||
|
a lot of data that needs to be copied, this should be set high. */
|
||||||
|
#define MEM_SIZE 10240
|
||||||
|
|
||||||
|
/* MEMP_NUM_PBUF: the number of memp struct pbufs. If the application
|
||||||
|
sends a lot of data out of ROM (or other static memory), this
|
||||||
|
should be set high. */
|
||||||
|
#define MEMP_NUM_PBUF 100
|
||||||
|
/* MEMP_NUM_RAW_PCB: the number of UDP protocol control blocks. One
|
||||||
|
per active RAW "connection". */
|
||||||
|
#define MEMP_NUM_RAW_PCB 3
|
||||||
|
/* MEMP_NUM_UDP_PCB: the number of UDP protocol control blocks. One
|
||||||
|
per active UDP "connection". */
|
||||||
|
#define MEMP_NUM_UDP_PCB 8
|
||||||
|
/* MEMP_NUM_TCP_PCB: the number of simultaneously active TCP
|
||||||
|
connections. */
|
||||||
|
#define MEMP_NUM_TCP_PCB 5
|
||||||
|
/* MEMP_NUM_TCP_PCB_LISTEN: the number of listening TCP
|
||||||
|
connections. */
|
||||||
|
#define MEMP_NUM_TCP_PCB_LISTEN 8
|
||||||
|
/* MEMP_NUM_TCP_SEG: the number of simultaneously queued TCP
|
||||||
|
segments. */
|
||||||
|
#define MEMP_NUM_TCP_SEG 16
|
||||||
|
/* MEMP_NUM_SYS_TIMEOUT: the number of simultaneously active
|
||||||
|
timeouts. */
|
||||||
|
#define MEMP_NUM_SYS_TIMEOUT 17
|
||||||
|
|
||||||
|
/* The following four are used only with the sequential API and can be
|
||||||
|
set to 0 if the application only will use the raw API. */
|
||||||
|
/* MEMP_NUM_NETBUF: the number of struct netbufs. */
|
||||||
|
#define MEMP_NUM_NETBUF 100
|
||||||
|
/* MEMP_NUM_NETCONN: the number of struct netconns. */
|
||||||
|
#define MEMP_NUM_NETCONN 64
|
||||||
|
/* MEMP_NUM_TCPIP_MSG_*: the number of struct tcpip_msg, which is used
|
||||||
|
for sequential API communication and incoming packets. Used in
|
||||||
|
src/api/tcpip.c. */
|
||||||
|
#define MEMP_NUM_TCPIP_MSG_API 16
|
||||||
|
#define MEMP_NUM_TCPIP_MSG_INPKT 16
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- Pbuf options ---------- */
|
||||||
|
/* PBUF_POOL_SIZE: the number of buffers in the pbuf pool. */
|
||||||
|
#define PBUF_POOL_SIZE 120
|
||||||
|
|
||||||
|
/* PBUF_POOL_BUFSIZE: the size of each pbuf in the pbuf pool. */
|
||||||
|
#define PBUF_POOL_BUFSIZE 256
|
||||||
|
|
||||||
|
/** SYS_LIGHTWEIGHT_PROT
|
||||||
|
* define SYS_LIGHTWEIGHT_PROT in lwipopts.h if you want inter-task protection
|
||||||
|
* for certain critical regions during buffer allocation, deallocation and memory
|
||||||
|
* allocation and deallocation.
|
||||||
|
*/
|
||||||
|
#define SYS_LIGHTWEIGHT_PROT (NO_SYS==0)
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- TCP options ---------- */
|
||||||
|
#define LWIP_TCP 1
|
||||||
|
#define TCP_TTL 255
|
||||||
|
|
||||||
|
#define LWIP_ALTCP (LWIP_TCP)
|
||||||
|
#ifdef LWIP_HAVE_MBEDTLS
|
||||||
|
#define LWIP_ALTCP_TLS (LWIP_TCP)
|
||||||
|
#define LWIP_ALTCP_TLS_MBEDTLS (LWIP_TCP)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/* Controls if TCP should queue segments that arrive out of
|
||||||
|
order. Define to 0 if your device is low on memory. */
|
||||||
|
#define TCP_QUEUE_OOSEQ 1
|
||||||
|
|
||||||
|
/* TCP Maximum segment size. */
|
||||||
|
#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. */
|
||||||
|
#define TCP_SND_QUEUELEN (4 * TCP_SND_BUF/TCP_MSS)
|
||||||
|
|
||||||
|
/* TCP writable space (bytes). This must be less than or equal
|
||||||
|
to TCP_SND_BUF. It is the amount of space which must be
|
||||||
|
available in the tcp snd_buf for select to return writable */
|
||||||
|
#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
|
||||||
|
|
||||||
|
/* Maximum number of retransmissions of SYN segments. */
|
||||||
|
#define TCP_SYNMAXRTX 4
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- ARP options ---------- */
|
||||||
|
#define LWIP_ARP 1
|
||||||
|
#define ARP_TABLE_SIZE 10
|
||||||
|
#define ARP_QUEUEING 1
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- IP options ---------- */
|
||||||
|
/* Define IP_FORWARD to 1 if you wish to have the ability to forward
|
||||||
|
IP packets across network interfaces. If you are going to run lwIP
|
||||||
|
on a device with only one network interface, define this to 0. */
|
||||||
|
#define IP_FORWARD 1
|
||||||
|
|
||||||
|
/* IP reassembly and segmentation.These are orthogonal even
|
||||||
|
* if they both deal with IP fragments */
|
||||||
|
#define IP_REASSEMBLY 1
|
||||||
|
#define IP_REASS_MAX_PBUFS (10 * ((1500 + PBUF_POOL_BUFSIZE - 1) / PBUF_POOL_BUFSIZE))
|
||||||
|
#define MEMP_NUM_REASSDATA IP_REASS_MAX_PBUFS
|
||||||
|
#define IP_FRAG 1
|
||||||
|
#define IPV6_FRAG_COPYHEADER 1
|
||||||
|
|
||||||
|
/* ---------- ICMP options ---------- */
|
||||||
|
#define ICMP_TTL 255
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- DHCP options ---------- */
|
||||||
|
/* Define LWIP_DHCP to 1 if you want DHCP configuration of
|
||||||
|
interfaces. */
|
||||||
|
#define LWIP_DHCP 1
|
||||||
|
|
||||||
|
/* 1 if you want to do an ARP check on the offered address
|
||||||
|
(recommended). */
|
||||||
|
#define DHCP_DOES_ARP_CHECK (LWIP_DHCP)
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- AUTOIP options ------- */
|
||||||
|
#define LWIP_AUTOIP (LWIP_DHCP)
|
||||||
|
#define LWIP_DHCP_AUTOIP_COOP (LWIP_DHCP && LWIP_AUTOIP)
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- UDP options ---------- */
|
||||||
|
#define LWIP_UDP 1
|
||||||
|
#define LWIP_UDPLITE LWIP_UDP
|
||||||
|
#define UDP_TTL 255
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- RAW options ---------- */
|
||||||
|
#define LWIP_RAW 1
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------- Statistics options ---------- */
|
||||||
|
|
||||||
|
#define LWIP_STATS 1
|
||||||
|
#define LWIP_STATS_DISPLAY 1
|
||||||
|
|
||||||
|
#if LWIP_STATS
|
||||||
|
#define LINK_STATS 1
|
||||||
|
#define IP_STATS 1
|
||||||
|
#define ICMP_STATS 1
|
||||||
|
#define IGMP_STATS 1
|
||||||
|
#define IPFRAG_STATS 1
|
||||||
|
#define UDP_STATS 1
|
||||||
|
#define TCP_STATS 1
|
||||||
|
#define MEM_STATS 1
|
||||||
|
#define MEMP_STATS 1
|
||||||
|
#define PBUF_STATS 1
|
||||||
|
#define SYS_STATS 1
|
||||||
|
#endif /* LWIP_STATS */
|
||||||
|
|
||||||
|
/* ---------- NETBIOS options ---------- */
|
||||||
|
#define LWIP_NETBIOS_RESPOND_NAME_QUERY 1
|
||||||
|
|
||||||
|
/* ---------- PPP options ---------- */
|
||||||
|
|
||||||
|
#define PPP_SUPPORT 1 /* Set > 0 for PPP */
|
||||||
|
|
||||||
|
#if PPP_SUPPORT
|
||||||
|
|
||||||
|
#define NUM_PPP 1 /* Max PPP sessions. */
|
||||||
|
|
||||||
|
|
||||||
|
/* Select modules to enable. Ideally these would be set in the makefile but
|
||||||
|
* we're limited by the command line length so you need to modify the settings
|
||||||
|
* in this file.
|
||||||
|
*/
|
||||||
|
#define PPPOE_SUPPORT 0
|
||||||
|
#define PPPOS_SUPPORT 1
|
||||||
|
|
||||||
|
#define PAP_SUPPORT 0 /* Set > 0 for PAP. */
|
||||||
|
#define CHAP_SUPPORT 0 /* Set > 0 for CHAP. */
|
||||||
|
#define MSCHAP_SUPPORT 0 /* Set > 0 for MSCHAP */
|
||||||
|
#define CBCP_SUPPORT 0 /* Set > 0 for CBCP (NOT FUNCTIONAL!) */
|
||||||
|
#define CCP_SUPPORT 0 /* Set > 0 for CCP */
|
||||||
|
#define VJ_SUPPORT 1 /* Set > 0 for VJ header compression. */
|
||||||
|
#define MD5_SUPPORT 0 /* Set > 0 for MD5 (see also CHAP) */
|
||||||
|
|
||||||
|
#endif /* PPP_SUPPORT */
|
||||||
|
|
||||||
|
#endif /* LWIP_OPTTEST_FILE */
|
||||||
|
|
||||||
|
/* The following defines must be done even in OPTTEST mode: */
|
||||||
|
|
||||||
|
#if !defined(NO_SYS) || !NO_SYS /* default is 0 */
|
||||||
|
void sys_check_core_locking(void);
|
||||||
|
#define LWIP_ASSERT_CORE_LOCKED() sys_check_core_locking()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LWIP_PLATFORM_ASSERT
|
||||||
|
/* Define LWIP_PLATFORM_ASSERT to something to catch missing stdio.h includes */
|
||||||
|
void ap_networking_platform_assert(const char *msg, int line, const char *file);
|
||||||
|
#define LWIP_PLATFORM_ASSERT(x) ap_networking_platform_assert(x, __LINE__, __FILE__)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
map LWIP debugging onto ap_networking_printf to allow for easier
|
||||||
|
redirection to a file or dedicated serial port
|
||||||
|
*/
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
int ap_networking_printf(const char *fmt, ...);
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#define LWIP_PLATFORM_DIAG(x) do {ap_networking_printf x; } while(0)
|
||||||
|
|
||||||
|
// #define AP_NETWORKING_LWIP_DEBUG_FILE "lwip.log"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
538
libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp
Normal file
538
libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp
Normal file
@ -0,0 +1,538 @@
|
|||||||
|
/*
|
||||||
|
port of lwip to ArduPilot AP_HAL
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include <AP_HAL/Semaphores.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
|
#include <string.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <errno.h>
|
||||||
|
|
||||||
|
#include <lwipopts.h>
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#include "lwip/debug.h"
|
||||||
|
#include "lwip/def.h"
|
||||||
|
#include "lwip/sys.h"
|
||||||
|
#include "lwip/opt.h"
|
||||||
|
#include "lwip/stats.h"
|
||||||
|
#include "lwip/tcpip.h"
|
||||||
|
}
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
#include <semaphore.h>
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
#include "hal.h"
|
||||||
|
#include "../../../libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
|
unsigned int
|
||||||
|
lwip_port_rand(void)
|
||||||
|
{
|
||||||
|
return (u32_t)rand();
|
||||||
|
}
|
||||||
|
|
||||||
|
static HAL_Semaphore lwprot_mutex;
|
||||||
|
static HAL_Semaphore tcpip_mutex;
|
||||||
|
|
||||||
|
struct sys_mbox_msg {
|
||||||
|
struct sys_mbox_msg *next;
|
||||||
|
void *msg;
|
||||||
|
};
|
||||||
|
|
||||||
|
#define SYS_MBOX_SIZE 128
|
||||||
|
|
||||||
|
struct sys_mbox {
|
||||||
|
int first, last;
|
||||||
|
void *msgs[SYS_MBOX_SIZE];
|
||||||
|
struct sys_sem *not_empty;
|
||||||
|
struct sys_sem *not_full;
|
||||||
|
struct sys_sem *mutex;
|
||||||
|
int wait_send;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct sys_sem {
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
sem_t sem;
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
semaphore_t sem;
|
||||||
|
#else
|
||||||
|
#error "Need sys_sem implementation"
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
static struct sys_sem *sys_sem_new_internal(u8_t count);
|
||||||
|
static void sys_sem_free_internal(struct sys_sem *sem);
|
||||||
|
|
||||||
|
/* Threads */
|
||||||
|
|
||||||
|
struct thread_wrapper_data {
|
||||||
|
lwip_thread_fn function;
|
||||||
|
void *arg;
|
||||||
|
};
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
static void *
|
||||||
|
thread_wrapper(void *arg)
|
||||||
|
{
|
||||||
|
auto *thread_data = (struct thread_wrapper_data *)arg;
|
||||||
|
thread_data->function(thread_data->arg);
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
static void
|
||||||
|
thread_wrapper(void *arg)
|
||||||
|
{
|
||||||
|
auto *thread_data = (struct thread_wrapper_data *)arg;
|
||||||
|
thread_data->function(thread_data->arg);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
sys_thread_t
|
||||||
|
sys_thread_new(const char *name, lwip_thread_fn function, void *arg, int stacksize, int prio)
|
||||||
|
{
|
||||||
|
sys_thread_t ret = nullptr;
|
||||||
|
struct thread_wrapper_data *thread_data;
|
||||||
|
|
||||||
|
thread_data = new thread_wrapper_data;
|
||||||
|
thread_data->arg = arg;
|
||||||
|
thread_data->function = function;
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
pthread_t t;
|
||||||
|
if (pthread_create(&t, NULL, thread_wrapper, thread_data) == 0) {
|
||||||
|
pthread_setname_np(t, name);
|
||||||
|
ret = (void*)t;
|
||||||
|
}
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
ret = thread_create_alloc(THD_WORKING_AREA_SIZE(stacksize+1024),
|
||||||
|
name,
|
||||||
|
prio+60, // need to use HAL thread call
|
||||||
|
thread_wrapper,
|
||||||
|
thread_data);
|
||||||
|
#endif
|
||||||
|
if (ret == nullptr) {
|
||||||
|
AP_HAL::panic("Failed to create thread %s", name);
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
void sys_lock_tcpip_core(void)
|
||||||
|
{
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
|
tcpip_mutex.take_blocking();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void sys_unlock_tcpip_core(void)
|
||||||
|
{
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
|
tcpip_mutex.give();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void sys_mark_tcpip_thread(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void sys_check_core_locking(void)
|
||||||
|
{
|
||||||
|
/* Embedded systems should check we are NOT in an interrupt
|
||||||
|
* context here */
|
||||||
|
}
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------------------*/
|
||||||
|
/* Mailbox */
|
||||||
|
err_t
|
||||||
|
sys_mbox_new(struct sys_mbox **mb, int size)
|
||||||
|
{
|
||||||
|
struct sys_mbox *mbox;
|
||||||
|
LWIP_UNUSED_ARG(size);
|
||||||
|
|
||||||
|
mbox = new sys_mbox;
|
||||||
|
if (mbox == NULL) {
|
||||||
|
return ERR_MEM;
|
||||||
|
}
|
||||||
|
mbox->first = mbox->last = 0;
|
||||||
|
mbox->not_empty = sys_sem_new_internal(0);
|
||||||
|
mbox->not_full = sys_sem_new_internal(0);
|
||||||
|
mbox->mutex = sys_sem_new_internal(1);
|
||||||
|
mbox->wait_send = 0;
|
||||||
|
|
||||||
|
*mb = mbox;
|
||||||
|
return ERR_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
sys_mbox_free(struct sys_mbox **mb)
|
||||||
|
{
|
||||||
|
if ((mb != NULL) && (*mb != SYS_MBOX_NULL)) {
|
||||||
|
struct sys_mbox *mbox = *mb;
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
|
||||||
|
sys_sem_free_internal(mbox->not_empty);
|
||||||
|
sys_sem_free_internal(mbox->not_full);
|
||||||
|
sys_sem_free_internal(mbox->mutex);
|
||||||
|
mbox->not_empty = mbox->not_full = mbox->mutex = NULL;
|
||||||
|
/* LWIP_DEBUGF("sys_mbox_free: mbox 0x%lx\n", mbox); */
|
||||||
|
delete mbox;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
err_t
|
||||||
|
sys_mbox_trypost(struct sys_mbox **mb, void *msg)
|
||||||
|
{
|
||||||
|
u8_t first;
|
||||||
|
struct sys_mbox *mbox;
|
||||||
|
LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL));
|
||||||
|
mbox = *mb;
|
||||||
|
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
|
||||||
|
LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_trypost: mbox %p msg %p\n",
|
||||||
|
(void *)mbox, (void *)msg));
|
||||||
|
|
||||||
|
if ((mbox->last + 1) >= (mbox->first + SYS_MBOX_SIZE)) {
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
return ERR_MEM;
|
||||||
|
}
|
||||||
|
|
||||||
|
mbox->msgs[mbox->last % SYS_MBOX_SIZE] = msg;
|
||||||
|
|
||||||
|
if (mbox->last == mbox->first) {
|
||||||
|
first = 1;
|
||||||
|
} else {
|
||||||
|
first = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
mbox->last++;
|
||||||
|
|
||||||
|
if (first) {
|
||||||
|
sys_sem_signal(&mbox->not_empty);
|
||||||
|
}
|
||||||
|
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
|
||||||
|
return ERR_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
sys_mbox_post(struct sys_mbox **mb, void *msg)
|
||||||
|
{
|
||||||
|
u8_t first;
|
||||||
|
struct sys_mbox *mbox;
|
||||||
|
LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL));
|
||||||
|
mbox = *mb;
|
||||||
|
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
|
||||||
|
LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_post: mbox %p msg %p\n", (void *)mbox, (void *)msg));
|
||||||
|
|
||||||
|
while ((mbox->last + 1) >= (mbox->first + SYS_MBOX_SIZE)) {
|
||||||
|
mbox->wait_send++;
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
sys_arch_sem_wait(&mbox->not_full, 0);
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
mbox->wait_send--;
|
||||||
|
}
|
||||||
|
|
||||||
|
mbox->msgs[mbox->last % SYS_MBOX_SIZE] = msg;
|
||||||
|
|
||||||
|
if (mbox->last == mbox->first) {
|
||||||
|
first = 1;
|
||||||
|
} else {
|
||||||
|
first = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
mbox->last++;
|
||||||
|
|
||||||
|
if (first) {
|
||||||
|
sys_sem_signal(&mbox->not_empty);
|
||||||
|
}
|
||||||
|
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
}
|
||||||
|
|
||||||
|
u32_t
|
||||||
|
sys_arch_mbox_tryfetch(struct sys_mbox **mb, void **msg)
|
||||||
|
{
|
||||||
|
struct sys_mbox *mbox = *mb;
|
||||||
|
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
|
||||||
|
if (mbox->first == mbox->last) {
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
return SYS_MBOX_EMPTY;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (msg != NULL) {
|
||||||
|
LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_tryfetch: mbox %p msg %p\n", (void *)mbox, *msg));
|
||||||
|
*msg = mbox->msgs[mbox->first % SYS_MBOX_SIZE];
|
||||||
|
} else {
|
||||||
|
LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_tryfetch: mbox %p, null msg\n", (void *)mbox));
|
||||||
|
}
|
||||||
|
|
||||||
|
mbox->first++;
|
||||||
|
|
||||||
|
if (mbox->wait_send) {
|
||||||
|
sys_sem_signal(&mbox->not_full);
|
||||||
|
}
|
||||||
|
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
u32_t
|
||||||
|
sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout)
|
||||||
|
{
|
||||||
|
struct sys_mbox *mbox;
|
||||||
|
LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL));
|
||||||
|
mbox = *mb;
|
||||||
|
|
||||||
|
/* The mutex lock is quick so we don't bother with the timeout
|
||||||
|
stuff here. */
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
|
||||||
|
while (mbox->first == mbox->last) {
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
|
||||||
|
/* We block while waiting for a mail to arrive in the mailbox. We
|
||||||
|
must be prepared to timeout. */
|
||||||
|
if (timeout != 0) {
|
||||||
|
u32_t time_needed = sys_arch_sem_wait(&mbox->not_empty, timeout);
|
||||||
|
|
||||||
|
if (time_needed == SYS_ARCH_TIMEOUT) {
|
||||||
|
return SYS_ARCH_TIMEOUT;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sys_arch_sem_wait(&mbox->not_empty, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
sys_arch_sem_wait(&mbox->mutex, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (msg != NULL) {
|
||||||
|
LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_fetch: mbox %p msg %p\n", (void *)mbox, *msg));
|
||||||
|
*msg = mbox->msgs[mbox->first % SYS_MBOX_SIZE];
|
||||||
|
} else {
|
||||||
|
LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_fetch: mbox %p, null msg\n", (void *)mbox));
|
||||||
|
}
|
||||||
|
|
||||||
|
mbox->first++;
|
||||||
|
|
||||||
|
if (mbox->wait_send) {
|
||||||
|
sys_sem_signal(&mbox->not_full);
|
||||||
|
}
|
||||||
|
|
||||||
|
sys_sem_signal(&mbox->mutex);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------------------*/
|
||||||
|
/* Semaphore */
|
||||||
|
static struct sys_sem *
|
||||||
|
sys_sem_new_internal(u8_t count)
|
||||||
|
{
|
||||||
|
auto *ret = new sys_sem;
|
||||||
|
if (ret != nullptr) {
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
sem_init(&ret->sem, 0, count);
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
chSemObjectInit(&ret->sem, (cnt_t)count);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
err_t
|
||||||
|
sys_sem_new(struct sys_sem **sem, u8_t count)
|
||||||
|
{
|
||||||
|
*sem = sys_sem_new_internal(count);
|
||||||
|
if (*sem == NULL) {
|
||||||
|
return ERR_MEM;
|
||||||
|
}
|
||||||
|
return ERR_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
u32_t
|
||||||
|
sys_arch_sem_wait(struct sys_sem **s, u32_t timeout_ms)
|
||||||
|
{
|
||||||
|
struct sys_sem *sem = *s;
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
if (timeout_ms == 0) {
|
||||||
|
sem_wait(&sem->sem);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
struct timespec ts;
|
||||||
|
if (clock_gettime(CLOCK_REALTIME, &ts) != 0) {
|
||||||
|
return SYS_ARCH_TIMEOUT;
|
||||||
|
}
|
||||||
|
ts.tv_sec += timeout_ms/1000UL;
|
||||||
|
ts.tv_nsec += (timeout_ms % 1000U) * 1000000UL;
|
||||||
|
if (ts.tv_nsec >= 1000000000L) {
|
||||||
|
ts.tv_sec++;
|
||||||
|
ts.tv_nsec -= 1000000000L;
|
||||||
|
}
|
||||||
|
auto ret = sem_timedwait(&sem->sem, &ts);
|
||||||
|
if (ret != 0) {
|
||||||
|
return SYS_ARCH_TIMEOUT;
|
||||||
|
}
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
chSysLock();
|
||||||
|
sysinterval_t tmo = timeout_ms > 0 ? MIN(TIME_MAX_INTERVAL, TIME_MS2I((time_msecs_t)timeout_ms)) : TIME_INFINITE;
|
||||||
|
if (chSemWaitTimeoutS(&sem->sem, tmo) != MSG_OK) {
|
||||||
|
chSysUnlock();
|
||||||
|
return SYS_ARCH_TIMEOUT;
|
||||||
|
}
|
||||||
|
chSysUnlock();
|
||||||
|
#endif
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
sys_sem_signal(struct sys_sem **s)
|
||||||
|
{
|
||||||
|
struct sys_sem *sem = *s;
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
sem_post(&sem->sem);
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
chSemSignal(&sem->sem);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void
|
||||||
|
sys_sem_free_internal(struct sys_sem *sem)
|
||||||
|
{
|
||||||
|
delete sem;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
sys_sem_free(struct sys_sem **sem)
|
||||||
|
{
|
||||||
|
if ((sem != NULL) && (*sem != SYS_SEM_NULL)) {
|
||||||
|
sys_sem_free_internal(*sem);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------------------*/
|
||||||
|
/* Mutex */
|
||||||
|
/** Create a new mutex
|
||||||
|
* @param mutex pointer to the mutex to create
|
||||||
|
* @return a new mutex */
|
||||||
|
err_t
|
||||||
|
sys_mutex_new(struct sys_mutex **mutex)
|
||||||
|
{
|
||||||
|
auto *sem = new HAL_Semaphore;
|
||||||
|
if (sem == nullptr) {
|
||||||
|
return ERR_MEM;
|
||||||
|
}
|
||||||
|
*mutex = (struct sys_mutex *)sem;
|
||||||
|
return ERR_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Lock a mutex
|
||||||
|
* @param mutex the mutex to lock */
|
||||||
|
void
|
||||||
|
sys_mutex_lock(struct sys_mutex **mutex)
|
||||||
|
{
|
||||||
|
auto *sem = (HAL_Semaphore *)*mutex;
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
|
sem->take_blocking();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Unlock a mutex
|
||||||
|
* @param mutex the mutex to unlock */
|
||||||
|
void
|
||||||
|
sys_mutex_unlock(struct sys_mutex **mutex)
|
||||||
|
{
|
||||||
|
auto *sem = (HAL_Semaphore *)*mutex;
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
|
sem->give();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Delete a mutex
|
||||||
|
* @param mutex the mutex to delete */
|
||||||
|
void
|
||||||
|
sys_mutex_free(struct sys_mutex **mutex)
|
||||||
|
{
|
||||||
|
auto *sem = (HAL_Semaphore *)*mutex;
|
||||||
|
delete sem;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------------------*/
|
||||||
|
/* Time */
|
||||||
|
u32_t
|
||||||
|
sys_now(void)
|
||||||
|
{
|
||||||
|
return AP_HAL::millis();
|
||||||
|
}
|
||||||
|
|
||||||
|
u32_t
|
||||||
|
sys_jiffies(void)
|
||||||
|
{
|
||||||
|
return AP_HAL::micros();
|
||||||
|
}
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------------------*/
|
||||||
|
/* Init */
|
||||||
|
|
||||||
|
void
|
||||||
|
sys_init(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------------------*/
|
||||||
|
/* Critical section */
|
||||||
|
/** sys_prot_t sys_arch_protect(void)
|
||||||
|
|
||||||
|
This optional function does a "fast" critical region protection and returns
|
||||||
|
the previous protection level. This function is only called during very short
|
||||||
|
critical regions. An embedded system which supports ISR-based drivers might
|
||||||
|
want to implement this function by disabling interrupts. Task-based systems
|
||||||
|
might want to implement this by using a mutex or disabling tasking. This
|
||||||
|
function should support recursive calls from the same task or interrupt. In
|
||||||
|
other words, sys_arch_protect() could be called while already protected. In
|
||||||
|
that case the return value indicates that it is already protected.
|
||||||
|
|
||||||
|
sys_arch_protect() is only required if your port is supporting an operating
|
||||||
|
system.
|
||||||
|
*/
|
||||||
|
sys_prot_t
|
||||||
|
sys_arch_protect(void)
|
||||||
|
{
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
|
lwprot_mutex.take_blocking();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/** void sys_arch_unprotect(sys_prot_t pval)
|
||||||
|
|
||||||
|
This optional function does a "fast" set of critical region protection to the
|
||||||
|
value specified by pval. See the documentation for sys_arch_protect() for
|
||||||
|
more information. This function is only required if your port is supporting
|
||||||
|
an operating system.
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
sys_arch_unprotect(sys_prot_t pval)
|
||||||
|
{
|
||||||
|
LWIP_UNUSED_ARG(pval);
|
||||||
|
if (hal.scheduler != nullptr) {
|
||||||
|
lwprot_mutex.give();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
21
libraries/AP_Networking/lwip_hal/include/arch/cc.h
Normal file
21
libraries/AP_Networking/lwip_hal/include/arch/cc.h
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <sys/select.h>
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define LWIP_ERRNO_STDINCLUDE 1
|
||||||
|
|
||||||
|
extern unsigned int lwip_port_rand(void);
|
||||||
|
#define LWIP_RAND() (lwip_port_rand())
|
||||||
|
|
||||||
|
typedef uint32_t sys_prot_t;
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
49
libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h
Normal file
49
libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h
Normal file
@ -0,0 +1,49 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define SYS_MBOX_NULL NULL
|
||||||
|
#define SYS_SEM_NULL NULL
|
||||||
|
|
||||||
|
/*typedef u32_t sys_prot_t;*/
|
||||||
|
|
||||||
|
struct sys_sem;
|
||||||
|
typedef struct sys_sem * sys_sem_t;
|
||||||
|
#define sys_sem_valid(sem) (((sem) != NULL) && (*(sem) != NULL))
|
||||||
|
#define sys_sem_valid_val(sem) ((sem) != NULL)
|
||||||
|
#define sys_sem_set_invalid(sem) do { if((sem) != NULL) { *(sem) = NULL; }}while(0)
|
||||||
|
#define sys_sem_set_invalid_val(sem) do { (sem) = NULL; }while(0)
|
||||||
|
|
||||||
|
struct sys_mutex;
|
||||||
|
typedef struct sys_mutex * sys_mutex_t;
|
||||||
|
#define sys_mutex_valid(mutex) sys_sem_valid(mutex)
|
||||||
|
#define sys_mutex_set_invalid(mutex) sys_sem_set_invalid(mutex)
|
||||||
|
|
||||||
|
struct sys_mbox;
|
||||||
|
typedef struct sys_mbox * sys_mbox_t;
|
||||||
|
#define sys_mbox_valid(mbox) sys_sem_valid(mbox)
|
||||||
|
#define sys_mbox_valid_val(mbox) sys_sem_valid_val(mbox)
|
||||||
|
#define sys_mbox_set_invalid(mbox) sys_sem_set_invalid(mbox)
|
||||||
|
#define sys_mbox_set_invalid_val(mbox) sys_sem_set_invalid_val(mbox)
|
||||||
|
|
||||||
|
typedef void *sys_thread_t;
|
||||||
|
|
||||||
|
void sys_mark_tcpip_thread(void);
|
||||||
|
#define LWIP_MARK_TCPIP_THREAD() sys_mark_tcpip_thread()
|
||||||
|
|
||||||
|
#if LWIP_TCPIP_CORE_LOCKING
|
||||||
|
void sys_lock_tcpip_core(void);
|
||||||
|
#define LOCK_TCPIP_CORE() sys_lock_tcpip_core()
|
||||||
|
void sys_unlock_tcpip_core(void);
|
||||||
|
#define UNLOCK_TCPIP_CORE() sys_unlock_tcpip_core()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
struct timeval;
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
36
libraries/AP_Networking/wscript
Normal file
36
libraries/AP_Networking/wscript
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
|
||||||
|
import pathlib
|
||||||
|
|
||||||
|
|
||||||
|
def configure(cfg):
|
||||||
|
extra_src = [
|
||||||
|
'modules/ChibiOS/ext/lwip/src/core/*c',
|
||||||
|
'modules/ChibiOS/ext/lwip/src/core/ipv4/*c',
|
||||||
|
'modules/ChibiOS/ext/lwip/src/api/*c',
|
||||||
|
'modules/ChibiOS/ext/lwip/src/netif/*c',
|
||||||
|
'modules/ChibiOS/ext/lwip/src/netif/ppp/*c',
|
||||||
|
]
|
||||||
|
|
||||||
|
extra_src_inc = [
|
||||||
|
'modules/ChibiOS/ext/lwip/src/include',
|
||||||
|
]
|
||||||
|
|
||||||
|
if cfg.env.BOARD_CLASS == "SITL":
|
||||||
|
extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp'])
|
||||||
|
extra_src_inc.extend(['libraries/AP_Networking/config',
|
||||||
|
'libraries/AP_Networking/lwip_hal/include'])
|
||||||
|
|
||||||
|
if cfg.env.BOARD_CLASS == "ChibiOS":
|
||||||
|
extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp'])
|
||||||
|
extra_src_inc.extend(['libraries/AP_Networking/config',
|
||||||
|
'libraries/AP_Networking/lwip_hal/include'])
|
||||||
|
|
||||||
|
cfg.env.AP_LIB_EXTRA_SOURCES['AP_Networking'] = []
|
||||||
|
for pattern in extra_src:
|
||||||
|
s = cfg.srcnode.ant_glob(pattern, dir=False, src=True)
|
||||||
|
for x in s:
|
||||||
|
cfg.env.AP_LIB_EXTRA_SOURCES['AP_Networking'].append(str(x))
|
||||||
|
|
||||||
|
for inc in extra_src_inc:
|
||||||
|
cfg.env.INCLUDES += [str(cfg.srcnode.make_node(inc))]
|
Loading…
Reference in New Issue
Block a user