AP_Networking: cleanup backend defines

This commit is contained in:
Tom Pittenger 2023-11-12 14:09:58 -08:00 committed by Andrew Tridgell
parent d2984cbd99
commit bd97dc4de5
6 changed files with 53 additions and 23 deletions

View File

@ -4,13 +4,14 @@
#if AP_NETWORKING_ENABLED
#include "AP_Networking.h"
#include "AP_Networking_ChibiOS.h"
#include "AP_Networking_backend.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_Math/crc.h>
extern const AP_HAL::HAL& hal;
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#if AP_NETWORKING_BACKEND_CHIBIOS
#include "AP_Networking_ChibiOS.h"
#include <hal_mii.h>
#include <lwip/sockets.h>
#else
@ -96,7 +97,7 @@ void AP_Networking::init()
param.macaddr.set_default_address_byte(5, crc.bytes[2]);
}
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#if AP_NETWORKING_BACKEND_CHIBIOS
backend = new AP_Networking_ChibiOS(*this);
#endif
@ -211,6 +212,23 @@ bool AP_Networking::convert_str_to_macaddr(const char *mac_str, uint8_t addr[6])
return true;
}
// returns the 32bit value of the active IP address that is currently in use
uint32_t AP_Networking::get_ip_active() const
{
return backend?backend->activeSettings.ip:0;
}
// returns the 32bit value of the active Netmask that is currently in use
uint32_t AP_Networking::get_netmask_active() const
{
return backend?backend->activeSettings.nm:0;
}
uint32_t AP_Networking::get_gateway_active() const
{
return backend?backend->activeSettings.gw:0;
}
AP_Networking *AP_Networking::singleton;
namespace AP

View File

@ -4,7 +4,6 @@
#include "AP_Networking_Config.h"
#if AP_NETWORKING_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include "AP_Networking_address.h"
@ -14,9 +13,14 @@
Note! all uint32_t IPv4 addresses are in host byte order
*/
// declare backend classes
class AP_Networking_backend;
class AP_Networking_ChibiOS;
class AP_Networking
{
public:
friend class AP_Networking_backend;
friend class AP_Networking_ChibiOS;
AP_Networking();
@ -54,10 +58,7 @@ public:
}
// returns the 32bit value of the active IP address that is currently in use
uint32_t get_ip_active() const
{
return backend?backend->activeSettings.ip:0;
}
uint32_t get_ip_active() const;
// returns the 32bit value of the user-parameter static IP address
uint32_t get_ip_param() const
@ -81,10 +82,7 @@ public:
}
// returns the 32bit value of the active Netmask that is currently in use
uint32_t get_netmask_active() const
{
return backend?backend->activeSettings.nm:0;
}
uint32_t get_netmask_active() const;
// returns the 32bit value of the of the user-parameter static Netmask
uint32_t get_netmask_param() const
@ -113,10 +111,7 @@ public:
param.netmask.set(convert_netmask_ip_to_bitcount(nm));
}
uint32_t get_gateway_active() const
{
return backend?backend->activeSettings.gw:0;
}
uint32_t get_gateway_active() const;
uint32_t get_gateway_param() const
{

View File

@ -1,11 +1,9 @@
#include "AP_Networking_Config.h"
#if AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#if AP_NETWORKING_BACKEND_CHIBIOS
#include "AP_Networking.h"
#include "AP_Networking_ChibiOS.h"
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#include <lwipthread.h>
@ -174,5 +172,5 @@ int32_t AP_Networking_ChibiOS::send_udp(struct udp_pcb *pcb, const ip4_addr_t &i
return err == ERR_OK ? data_len : err;
}
#endif // AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#endif // AP_NETWORKING_BACKEND_CHIBIOS

View File

@ -2,7 +2,7 @@
#include "AP_Networking_Config.h"
#if AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#if AP_NETWORKING_BACKEND_CHIBIOS
#include "AP_Networking_backend.h"
class AP_Networking_ChibiOS : public AP_Networking_backend
@ -25,5 +25,5 @@ private:
uint8_t macaddr[6];
};
#endif // AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#endif // AP_NETWORKING_BACKEND_CHIBIOS

View File

@ -4,7 +4,24 @@
#define AP_NETWORKING_ENABLED 0
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED
#define AP_NETWORKING_BACKEND_DEFAULT_ENABLED AP_NETWORKING_ENABLED
#endif
// ---------------------------
// Backends
// ---------------------------
#ifndef AP_NETWORKING_BACKEND_CHIBIOS
#define AP_NETWORKING_BACKEND_CHIBIOS AP_NETWORKING_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#endif
#define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS)
// ---------------------------
// IP Features
// ---------------------------
#if AP_NETWORKING_BACKEND_CHIBIOS
#define AP_NETWORKING_DHCP_AVAILABLE LWIP_DHCP
#else
#define AP_NETWORKING_DHCP_AVAILABLE 1 // for non-ChibiOS, assume it's available

View File

@ -4,6 +4,8 @@
#if AP_NETWORKING_ENABLED
#include "AP_Networking.h"
class AP_Networking;
class AP_Networking_backend