From 88b3f16fd27852258140a351a4e553b0b9472388 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 29 Nov 2023 14:16:31 -0800 Subject: [PATCH] AP_Networking: only show NET_IP,DHCP,GW,MASK,MAC if it's actually used --- libraries/AP_Networking/AP_Networking.cpp | 8 +++- libraries/AP_Networking/AP_Networking.h | 39 ++++++++++++++++++- .../AP_Networking/AP_Networking_ChibiOS.cpp | 4 -- .../AP_Networking/AP_Networking_Config.h | 25 ++++++++---- 4 files changed, 62 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 0349145f648dd..9cdb16027554e 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -31,6 +31,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @User: Advanced AP_GROUPINFO_FLAGS("ENABLED", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE), +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED // @Group: IPADDR // @Path: AP_Networking_address.cpp AP_SUBGROUPINFO(param.ipaddr, "IPADDR", 2, AP_Networking, AP_Networking_IPV4), @@ -43,6 +44,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @User: Advanced AP_GROUPINFO("NETMASK", 3, AP_Networking, param.netmask, AP_NETWORKING_DEFAULT_NETMASK), +#if AP_NETWORKING_DHCP_AVAILABLE // @Param: DHCP // @DisplayName: DHCP client // @Description: Enable/Disable DHCP client @@ -50,6 +52,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @RebootRequired: True // @User: Advanced AP_GROUPINFO("DHCP", 4, AP_Networking, param.dhcp, AP_NETWORKING_DEFAULT_DHCP_ENABLE), +#endif // @Group: GWADDR // @Path: AP_Networking_address.cpp @@ -58,6 +61,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Group: MACADDR // @Path: AP_Networking_macaddr.cpp AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC), +#endif // AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED #if AP_NETWORKING_TESTS_ENABLED // @Param: TESTS @@ -99,6 +103,7 @@ void AP_Networking::init() return; } +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED // set default MAC Address as lower 3 bytes of the CRC of the UID uint8_t uid[50]; uint8_t uid_len = sizeof(uid); @@ -113,6 +118,7 @@ void AP_Networking::init() param.macaddr.set_default_address_byte(4, crc.bytes[1]); param.macaddr.set_default_address_byte(5, crc.bytes[2]); } +#endif #if AP_NETWORKING_BACKEND_CHIBIOS backend = new AP_Networking_ChibiOS(*this); @@ -150,7 +156,7 @@ void AP_Networking::init() */ void AP_Networking::announce_address_changes() { - auto &as = backend->activeSettings; + const auto &as = backend->activeSettings; if (as.last_change_ms == 0 || as.last_change_ms == announce_ms) { // nothing changed and we've already printed it at least once. Nothing to do. diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 257a4950c7daf..b7ba4f6c03bb7 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -54,13 +54,22 @@ class AP_Networking // returns true if DHCP is enabled bool get_dhcp_enabled() const { +#if AP_NETWORKING_DHCP_AVAILABLE return param.dhcp; +#else + // DHCP is not available from our scope but could be enabled/controlled + // by the OS which is the case on Linux builds, including SITL + // TODO: ask the OS if DHCP is enabled + return false; +#endif } // Sets DHCP to be enabled or disabled void set_dhcp_enable(const bool enable) { +#if AP_NETWORKING_DHCP_AVAILABLE param.dhcp.set(enable); +#endif } // returns the 32bit value of the active IP address that is currently in use @@ -69,7 +78,12 @@ class AP_Networking // returns the 32bit value of the user-parameter static IP address uint32_t get_ip_param() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED return param.ipaddr.get_uint32(); +#else + // TODO: ask the OS for the IP address + return 0; +#endif } /* @@ -84,7 +98,9 @@ class AP_Networking // sets the user-parameter static IP address from a 32bit value void set_ip_param(const uint32_t ip) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED param.ipaddr.set_uint32(ip); +#endif } // returns the 32bit value of the active Netmask that is currently in use @@ -93,7 +109,12 @@ class AP_Networking // returns the 32bit value of the of the user-parameter static Netmask uint32_t get_netmask_param() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED return convert_netmask_bitcount_to_ip(param.netmask.get()); +#else + // TODO: ask the OS for the Netmask + return 0; +#endif } // returns a null terminated string of the active Netmask address. Example: "192.168.12.13" @@ -114,14 +135,21 @@ class AP_Networking void set_netmask_param(const uint32_t nm) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED param.netmask.set(convert_netmask_ip_to_bitcount(nm)); +#endif } uint32_t get_gateway_active() const; uint32_t get_gateway_param() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED return param.gwaddr.get_uint32(); +#else + // TODO: ask the OS for the Gateway + return 0; +#endif } const char *get_gateway_active_str() @@ -141,7 +169,9 @@ class AP_Networking void set_gateway_param(const uint32_t gw) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED param.gwaddr.set_uint32(gw); +#endif } // helper functions to convert between 32bit IP addresses and null terminated strings and back @@ -163,14 +193,19 @@ class AP_Networking void announce_address_changes(); struct { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED AP_Networking_IPV4 ipaddr{AP_NETWORKING_DEFAULT_STATIC_IP_ADDR}; AP_Int8 netmask; // bits to mask. example: (16 == 255.255.0.0) and (24 == 255.255.255.0) AP_Networking_IPV4 gwaddr{AP_NETWORKING_DEFAULT_STATIC_GW_ADDR}; - - AP_Int8 dhcp; AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR}; +#if AP_NETWORKING_DHCP_AVAILABLE + AP_Int8 dhcp; +#endif +#endif + AP_Int8 enabled; AP_Int32 options; + #if AP_NETWORKING_TESTS_ENABLED AP_Int32 tests; AP_Networking_IPV4 test_ipaddr{AP_NETWORKING_TEST_IP}; diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index 442efdc454a0a..692ca988fc186 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -102,10 +102,6 @@ bool AP_Networking_ChibiOS::init() return false; } -#if !AP_NETWORKING_DHCP_AVAILABLE - frontend.set_dhcp_enable(false); -#endif - lwip_options = new lwipthread_opts; if (frontend.get_dhcp_enabled()) { diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index bfc4af537f226..5d32334510dc5 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -8,16 +8,24 @@ #define AP_NETWORKING_BACKEND_DEFAULT_ENABLED AP_NETWORKING_ENABLED #endif +#ifndef AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED +// AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED should only be true if we have the ability to +// change the IP address. If not then the IP, GW, NetMask, MAC and DHCP params are hidden. +// This does not mean that the system/OS does not have the ability to set the IP, just that +// we have no control from this scope. For example, Linux systems (including SITL) have +// their own DHCP client running but we have no control over it. +#define AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) +#endif // --------------------------- // Backends // --------------------------- #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_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) #endif #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 #define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) @@ -25,10 +33,13 @@ // --------------------------- // 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 +#ifndef AP_NETWORKING_DHCP_AVAILABLE +// AP_NETWORKING_DHCP_AVAILABLE should only be true if, by setting the NET_DHCP parameter, +// we have the ability to turn on/off the DHCP client which effects the assigned IP address. +// Otherwise, param NET_DHCP will be hidden. This does not mean that the system/OS does not +// have DHCP, just that we have no control from this scope. For example, Linux systems +// (including SITL) have their own DHCP client running but we have no control over it. +#define AP_NETWORKING_DHCP_AVAILABLE (AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED || AP_NETWORKING_BACKEND_CHIBIOS) #endif @@ -38,7 +49,7 @@ // Default DHCP #ifndef AP_NETWORKING_DEFAULT_DHCP_ENABLE -#define AP_NETWORKING_DEFAULT_DHCP_ENABLE 1 +#define AP_NETWORKING_DEFAULT_DHCP_ENABLE AP_NETWORKING_DHCP_AVAILABLE #endif // Default Static IP Address: 192.168.13.14