AP_Networking: allow reuse of some of AP_Networking in bootloader

This commit is contained in:
Andrew Tridgell 2024-01-13 16:29:09 +11:00
parent 654b70da67
commit 9f646c8238
5 changed files with 41 additions and 14 deletions

View File

@ -214,10 +214,12 @@ void AP_Networking::announce_address_changes()
return;
}
#if AP_HAVE_GCS_SEND_TEXT
char ipstr[16];
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", SocketAPM::inet_addr_to_str(get_ip_active(), ipstr, sizeof(ipstr)));
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", SocketAPM::inet_addr_to_str(get_netmask_active(), ipstr, sizeof(ipstr)));
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", SocketAPM::inet_addr_to_str(get_gateway_active(), ipstr, sizeof(ipstr)));
#endif
announce_ms = as.last_change_ms;
}

View File

@ -13,6 +13,7 @@
#if LWIP_DHCP
#include <lwip/dhcp.h>
#endif
#include <lwip/etharp.h>
#include <hal.h>
#include "../../modules/ChibiOS/os/various/evtimer.h"
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
@ -62,11 +63,14 @@ bool AP_Networking_ChibiOS::allocate_buffers()
if (mem == nullptr) {
return false;
}
#ifndef HAL_BOOTLOADER_BUILD
// ensure our memory is aligned
// ref. Cortex-M7 peripherals PM0253, section 4.6.4 MPU region base address register
if (((uint32_t)mem) % size) {
AP_HAL::panic("Bad alignment of ETH memory");
}
#endif
// for total_size == 9240, size should be 16384 and (rasr-1) should be 13 (MPU_RASR_SIZE_16K)
const uint32_t rasr_size = MPU_RASR_SIZE(rasr-1);
@ -139,8 +143,8 @@ bool AP_Networking_ChibiOS::init()
void AP_Networking_ChibiOS::link_up_cb(void *p)
{
auto *driver = (AP_Networking_ChibiOS *)p;
#if LWIP_DHCP
auto *driver = (AP_Networking_ChibiOS *)p;
if (driver->frontend.get_dhcp_enabled()) {
dhcp_start(driver->thisif);
}
@ -149,8 +153,8 @@ void AP_Networking_ChibiOS::link_up_cb(void *p)
void AP_Networking_ChibiOS::link_down_cb(void *p)
{
auto *driver = (AP_Networking_ChibiOS *)p;
#if LWIP_DHCP
auto *driver = (AP_Networking_ChibiOS *)p;
if (driver->frontend.get_dhcp_enabled()) {
dhcp_stop(driver->thisif);
}

View File

@ -8,6 +8,7 @@
class AP_Networking_ChibiOS : public AP_Networking_Backend
{
public:
friend class BL_Network;
using AP_Networking_Backend::AP_Networking_Backend;
/* Do not allow copies */
@ -17,7 +18,7 @@ public:
void update() override;
private:
bool allocate_buffers(void);
static bool allocate_buffers(void);
void thread(void);
static void link_up_cb(void*);
static void link_down_cb(void*);

View File

@ -31,6 +31,8 @@
*/
#pragma once
#include "hwdef.h"
#ifdef __cplusplus
extern "C"
{
@ -78,13 +80,17 @@ extern "C"
#define LWIP_SNMP_V3 (LWIP_SNMP)
#endif
#define LWIP_DNS LWIP_UDP
#define LWIP_MDNS_RESPONDER LWIP_UDP
#define LWIP_DNS 0
#define LWIP_MDNS_RESPONDER 0
#define LWIP_NUM_NETIF_CLIENT_DATA (LWIP_MDNS_RESPONDER)
#ifndef LWIP_HAVE_LOOPIF
#define LWIP_HAVE_LOOPIF 1
#endif
#ifndef LWIP_NETIF_LOOPBACK
#define LWIP_NETIF_LOOPBACK 1
#endif
#define LWIP_LOOPBACK_MAX_PBUFS 10
#define TCP_LISTEN_BACKLOG 1
@ -254,14 +260,18 @@ a lot of data that needs to be copied, this should be set high. */
#define LWIP_ARP 1
#define ARP_TABLE_SIZE 10
#define ARP_QUEUEING 1
#ifndef ARP_PROXYARP_SUPPORT
#define ARP_PROXYARP_SUPPORT 1
#endif
/* ---------- 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. */
#ifndef IP_FORWARD
#define IP_FORWARD 1
#endif
/*
extra header space when forwarding for adding the ethernet header
@ -284,7 +294,9 @@ a lot of data that needs to be copied, this should be set high. */
/* ---------- DHCP options ---------- */
/* Define LWIP_DHCP to 1 if you want DHCP configuration of
interfaces. */
#ifndef LWIP_DHCP
#define LWIP_DHCP 1
#endif
/* 1 if you want to do an ARP check on the offered address
(recommended). */
@ -297,13 +309,15 @@ a lot of data that needs to be copied, this should be set high. */
/* ---------- UDP options ---------- */
#ifndef LWIP_UDP
#define LWIP_UDP 1
#endif
#define LWIP_UDPLITE LWIP_UDP
#define UDP_TTL 255
/* ---------- RAW options ---------- */
#define LWIP_RAW 1
#define LWIP_RAW 0
/* ---------- Statistics options ---------- */
@ -312,11 +326,13 @@ a lot of data that needs to be copied, this should be set high. */
#define LWIP_STATS_DISPLAY 0
/* ---------- NETBIOS options ---------- */
#define LWIP_NETBIOS_RESPOND_NAME_QUERY 1
#define LWIP_NETBIOS_RESPOND_NAME_QUERY 0
/* ---------- PPP options ---------- */
#ifndef PPP_SUPPORT
#define PPP_SUPPORT 1 /* Set > 0 for PPP */
#endif
#if PPP_SUPPORT
@ -328,7 +344,7 @@ a lot of data that needs to be copied, this should be set high. */
* in this file.
*/
#define PPPOE_SUPPORT 0
#define PPPOS_SUPPORT 1
#define PPPOS_SUPPORT PPP_SUPPORT
#define PAP_SUPPORT 0 /* Set > 0 for PAP. */
#define CHAP_SUPPORT 0 /* Set > 0 for CHAP. */

View File

@ -10,6 +10,10 @@
#include <AP_HAL/Semaphores.h>
#include <AP_Math/AP_Math.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
#endif
#include <string.h>
#include <sys/time.h>
#include <sys/types.h>
@ -63,8 +67,12 @@ public:
arg(_arg)
{}
bool create(const char *name, int stacksize, int prio) {
#ifdef HAL_BOOTLOADER_BUILD
return thread_create_alloc(MAX(stacksize,2048), name, 60, function, arg);
#else
return hal.scheduler->thread_create(
FUNCTOR_BIND_MEMBER(&ThreadWrapper::run, void), name, MAX(stacksize,2048), AP_HAL::Scheduler::PRIORITY_NET, prio);
#endif
}
private:
void run(void) {
@ -373,9 +381,7 @@ sys_init(void)
sys_prot_t
sys_arch_protect(void)
{
if (hal.scheduler != nullptr) {
lwprot_mutex.take_blocking();
}
lwprot_mutex.take_blocking();
return 0;
}
@ -383,9 +389,7 @@ void
sys_arch_unprotect(sys_prot_t pval)
{
LWIP_UNUSED_ARG(pval);
if (hal.scheduler != nullptr) {
lwprot_mutex.give();
}
lwprot_mutex.give();
}
#endif // AP_NETWORKING_NEED_LWIP