From 0dc2423623101e37757d4e11f99007551d17aec8 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sat, 25 Nov 2023 16:59:09 -0800 Subject: [PATCH] AP_Networking: only show NET_IP,DHCP,GW,MASK,MAC if it's actually used --- libraries/AP_Networking/AP_Networking.cpp | 4 +++ libraries/AP_Networking/AP_Networking.h | 28 +++++++++++++++++++ .../AP_Networking/AP_Networking_Config.h | 3 ++ 3 files changed, 35 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 7783adf77dac4e..368fc77d043a14 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 // @Group: IPADDR // @Path: AP_Networking_address.cpp AP_SUBGROUPINFO(param.ipaddr, "IPADDR", 2, AP_Networking, AP_Networking_IPV4), @@ -58,6 +59,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 #if AP_NETWORKING_TESTS_ENABLED // @Param: TESTS @@ -99,6 +101,7 @@ void AP_Networking::init() return; } +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS // 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 +116,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); diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index c931fc26982461..d93a9b6edf90b4 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -54,13 +54,19 @@ class AP_Networking // returns true if DHCP is enabled bool get_dhcp_enabled() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS return param.dhcp; +#else + return false; +#endif } // Sets DHCP to be enabled or disabled void set_dhcp_enable(const bool enable) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS param.dhcp.set(enable); +#endif } // returns the 32bit value of the active IP address that is currently in use @@ -69,7 +75,11 @@ 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 return param.ipaddr.get_uint32(); +#else + return 0; +#endif } /* @@ -84,7 +94,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 param.ipaddr.set_uint32(ip); +#endif } // returns the 32bit value of the active Netmask that is currently in use @@ -93,7 +105,11 @@ 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 return convert_netmask_bitcount_to_ip(param.netmask.get()); +#else + return 0; +#endif } // returns a null terminated string of the active Netmask address. Example: "192.168.12.13" @@ -114,14 +130,20 @@ class AP_Networking void set_netmask_param(const uint32_t nm) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS 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 return param.gwaddr.get_uint32(); +#else + return 0; +#endif } const char *get_gateway_active_str() @@ -141,7 +163,9 @@ class AP_Networking void set_gateway_param(const uint32_t gw) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS param.gwaddr.set_uint32(gw); +#endif } // helper functions to convert between 32bit IP addresses and null terminated strings and back @@ -163,14 +187,18 @@ class AP_Networking void announce_address_changes(); struct { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS 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}; +#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_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index bfc4af537f226d..41d1af2c8f4f44 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -8,6 +8,9 @@ #define AP_NETWORKING_BACKEND_DEFAULT_ENABLED AP_NETWORKING_ENABLED #endif +#ifndef AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS +#define AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CONFIG_HAL_BOARD != HAL_BOARD_SITL) +#endif // --------------------------- // Backends