Skip to content

Commit

Permalink
AP_Networking: only show NET_IP,DHCP,GW,MASK,MAC if it's actually used
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Nov 30, 2023
1 parent 9907713 commit 88b3f16
Show file tree
Hide file tree
Showing 4 changed files with 62 additions and 14 deletions.
8 changes: 7 additions & 1 deletion libraries/AP_Networking/AP_Networking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand All @@ -43,13 +44,15 @@ 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
// @Values: 0:Disable, 1:Enable
// @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
Expand All @@ -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
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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.
Expand Down
39 changes: 37 additions & 2 deletions libraries/AP_Networking/AP_Networking.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
}

/*
Expand All @@ -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
Expand All @@ -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"
Expand All @@ -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()
Expand All @@ -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
Expand All @@ -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};
Expand Down
4 changes: 0 additions & 4 deletions libraries/AP_Networking/AP_Networking_ChibiOS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()) {
Expand Down
25 changes: 18 additions & 7 deletions libraries/AP_Networking/AP_Networking_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,27 +8,38 @@
#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)

// ---------------------------
// 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


Expand All @@ -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
Expand Down

0 comments on commit 88b3f16

Please sign in to comment.