mirror of https://github.com/ArduPilot/ardupilot
AP_Networking: cleanup parameter handling and fixed lwip config
This commit is contained in:
parent
8bddd4168b
commit
5705c68954
|
@ -18,6 +18,7 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
const AP_Param::GroupInfo AP_Networking::var_info[] = {
|
||||
|
||||
// @Param: ENABLED
|
||||
|
@ -28,37 +29,9 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS("ENABLED", 0, AP_Networking, _param.enabled, 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// @Param: IPADDR0
|
||||
// @DisplayName: IPv4 Address MSB
|
||||
// @Description: Allows setting static IP address. Example: 192.xxx.xxx.xxx
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("IPADDR0", 1, AP_Networking, _param.ipaddr[0], AP_NETWORKING_DEFAULT_STATIC_IP_ADDR0),
|
||||
|
||||
// @Param: IPADDR1
|
||||
// @DisplayName: IPv4 Address 2nd byte
|
||||
// @Description: Allows setting static IP address. Example: xxx.168.xxx.xxx
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("IPADDR1", 2, AP_Networking, _param.ipaddr[1], AP_NETWORKING_DEFAULT_STATIC_IP_ADDR1),
|
||||
|
||||
// @Param: IPADDR2
|
||||
// @DisplayName: IPv4 Address 3rd byte
|
||||
// @Description: Allows setting static IP address. Example: xxx.xxx.13.xxx
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("IPADDR2", 3, AP_Networking, _param.ipaddr[2], AP_NETWORKING_DEFAULT_STATIC_IP_ADDR2),
|
||||
|
||||
// @Param: IPADDR3
|
||||
// @DisplayName: IPv4 Address LSB
|
||||
// @Description: Allows setting static IP address. Example: xxx.xxx.xxx.14
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("IPADDR3", 4, AP_Networking, _param.ipaddr[3], AP_NETWORKING_DEFAULT_STATIC_IP_ADDR3),
|
||||
// @Group: IPADDR
|
||||
// @Path: AP_Networking_address.cpp
|
||||
AP_SUBGROUPINFO(_param.ipaddr, "IPADDR", 1, AP_Networking, AP_Networking_IPV4),
|
||||
|
||||
// @Param: NETMASK
|
||||
// @DisplayName: IP Subnet mask
|
||||
|
@ -66,7 +39,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = {
|
|||
// @Range: 0 32
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("NETMASK", 5, AP_Networking, _param.netmask, AP_NETWORKING_DEFAULT_NETMASK),
|
||||
AP_GROUPINFO("NETMASK", 2, AP_Networking, _param.netmask, AP_NETWORKING_DEFAULT_NETMASK),
|
||||
|
||||
// @Param: DHCP
|
||||
// @DisplayName: DHCP client
|
||||
|
@ -74,87 +47,15 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = {
|
|||
// @Values: 0:Disable, 1:Enable
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DHCP", 6, AP_Networking, _param.dhcp, AP_NETWORKING_DEFAULT_DHCP_ENABLE),
|
||||
AP_GROUPINFO("DHCP", 3, AP_Networking, _param.dhcp, AP_NETWORKING_DEFAULT_DHCP_ENABLE),
|
||||
|
||||
// @Param: GWADDR0
|
||||
// @DisplayName: Gateway IP Address MSB
|
||||
// @Description: Allows setting static GW address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GWADDR0", 7, AP_Networking, _param.gwaddr[0], AP_NETWORKING_DEFAULT_STATIC_GW_ADDR0),
|
||||
// @Group: GWADDR
|
||||
// @Path: AP_Networking_address.cpp
|
||||
AP_SUBGROUPINFO(_param.gwaddr, "GWADDR", 4, AP_Networking, AP_Networking_IPV4),
|
||||
|
||||
// @Param: GWADDR1
|
||||
// @DisplayName: Gateway IP Address 2nd byte
|
||||
// @Description: Allows setting static GW address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GWADDR1", 8, AP_Networking, _param.gwaddr[1], AP_NETWORKING_DEFAULT_STATIC_GW_ADDR1),
|
||||
|
||||
// @Param: GWADDR2
|
||||
// @DisplayName: Gateway IP Address 3rd byte
|
||||
// @Description: Allows setting static GW address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GWADDR2", 9, AP_Networking, _param.gwaddr[2], AP_NETWORKING_DEFAULT_STATIC_GW_ADDR2),
|
||||
|
||||
// @Param: GWADDR3
|
||||
// @DisplayName: Gateway IP Address LSB
|
||||
// @Description: Allows setting static GW address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GWADDR3", 10, AP_Networking, _param.gwaddr[3], AP_NETWORKING_DEFAULT_STATIC_GW_ADDR3),
|
||||
|
||||
// @Param: MACADDR0
|
||||
// @DisplayName: MAC Address MSbyte
|
||||
// @Description: Allows setting MAC address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MACADDR0", 11, AP_Networking, _param.macaddr[0], AP_NETWORKING_DEFAULT_MAC_ADDR0),
|
||||
|
||||
// @Param: MACADDR1
|
||||
// @DisplayName: MAC Address 2nd byte
|
||||
// @Description: Allows setting MAC address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MACADDR1", 12, AP_Networking, _param.macaddr[1], AP_NETWORKING_DEFAULT_MAC_ADDR1),
|
||||
|
||||
// @Param: MACADDR2
|
||||
// @DisplayName: MAC Address 3rd byte
|
||||
// @Description: Allows setting MAC address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MACADDR2", 13, AP_Networking, _param.macaddr[2], AP_NETWORKING_DEFAULT_MAC_ADDR2),
|
||||
|
||||
// @Param: MACADDR3
|
||||
// @DisplayName: MAC Address 4th byte
|
||||
// @Description: Allows setting MAC address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MACADDR3", 14, AP_Networking, _param.macaddr[3], AP_NETWORKING_DEFAULT_MAC_ADDR3),
|
||||
|
||||
// @Param: MACADDR4
|
||||
// @DisplayName: MAC Address 5th byte
|
||||
// @Description: Allows setting MAC address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MACADDR4", 15, AP_Networking, _param.macaddr[4], AP_NETWORKING_DEFAULT_MAC_ADDR4),
|
||||
|
||||
// @Param: MACADDR5
|
||||
// @DisplayName: MAC Address LSb
|
||||
// @Description: Allows setting MAC address
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MACADDR5", 16, AP_Networking, _param.macaddr[5], AP_NETWORKING_DEFAULT_MAC_ADDR5),
|
||||
// @Group: MACADDR
|
||||
// @Path: AP_Networking_address.cpp
|
||||
AP_SUBGROUPINFO(_param.macaddr, "MACADDR", 5, AP_Networking, AP_Networking_MAC),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -249,9 +150,9 @@ void AP_Networking::init()
|
|||
uint8_t uuid_len = sizeof(uuid);
|
||||
const bool udid_is_ok = hal.util->get_system_id_unformatted(uuid, uuid_len) && uuid_len >= 3;
|
||||
if (udid_is_ok) {
|
||||
_param.macaddr[3].set_default(uuid[uuid_len-2]);
|
||||
_param.macaddr[4].set_default(uuid[uuid_len-1]);
|
||||
_param.macaddr[5].set_default(uuid[uuid_len-0]);
|
||||
for (uint8_t i=0; i<3; i++) {
|
||||
_param.macaddr.set_default_address_byte(i, uuid[uuid_len-3+i]);
|
||||
}
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
@ -266,13 +167,7 @@ void AP_Networking::init()
|
|||
return;
|
||||
}
|
||||
|
||||
const uint8_t localMACAddress[6] = {(uint8_t)_param.macaddr[0].get(),
|
||||
(uint8_t)_param.macaddr[1].get(),
|
||||
(uint8_t)_param.macaddr[2].get(),
|
||||
(uint8_t)_param.macaddr[3].get(),
|
||||
(uint8_t)_param.macaddr[4].get(),
|
||||
(uint8_t)_param.macaddr[5].get()
|
||||
};
|
||||
_param.macaddr.get_address(_activeSettings.macaddr);
|
||||
|
||||
#if !AP_NETWORKING_DHCP_AVAILABLE
|
||||
set_dhcp_enable(false);
|
||||
|
@ -292,14 +187,13 @@ void AP_Networking::init()
|
|||
addrMode = NET_ADDRESS_STATIC;
|
||||
}
|
||||
|
||||
struct lwipthread_opts netOptions = { (uint8_t *) localMACAddress,
|
||||
_activeSettings.ip,
|
||||
_activeSettings.nm,
|
||||
_activeSettings.gw,
|
||||
addrMode
|
||||
};
|
||||
lwip_options.macaddress = _activeSettings.macaddr;
|
||||
lwip_options.address = _activeSettings.ip;
|
||||
lwip_options.netmask = _activeSettings.nm;
|
||||
lwip_options.gateway = _activeSettings.gw;
|
||||
lwip_options.addrMode = addrMode;
|
||||
|
||||
lwipInit(&netOptions);
|
||||
lwipInit(&lwip_options);
|
||||
#endif
|
||||
|
||||
#if AP_NETWORKING_DHCP_AVAILABLE
|
||||
|
@ -390,7 +284,7 @@ uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip)
|
|||
return netmask_bitcount;
|
||||
}
|
||||
|
||||
uint32_t AP_Networking::convert_str_to_ip(char* ip_str)
|
||||
uint32_t AP_Networking::convert_str_to_ip(const char* ip_str)
|
||||
{
|
||||
uint32_t ip = 0;
|
||||
inet_pton(AF_INET, ip_str, &ip);
|
||||
|
@ -416,6 +310,33 @@ const char* AP_Networking::convert_ip_to_str(const uint32_t ip)
|
|||
return convert_ip_to_str(ip_array);
|
||||
}
|
||||
|
||||
/*
|
||||
convert a string to an ethernet MAC address
|
||||
*/
|
||||
bool AP_Networking::convert_str_to_macaddr(const char *mac_str, uint8_t addr[6])
|
||||
{
|
||||
if (strlen(mac_str) != 17) {
|
||||
return false;
|
||||
}
|
||||
char s2[18];
|
||||
strncpy(s2, mac_str, sizeof(s2)-1);
|
||||
s2[17] = 0;
|
||||
char *ptr = nullptr;
|
||||
const char *s = strtok_r(s2, ":", &ptr);
|
||||
for (uint8_t i=0; i<6; i++) {
|
||||
if (s == nullptr) {
|
||||
return false;
|
||||
}
|
||||
auto v = strtoul(s, nullptr, 16);
|
||||
if (v > 255) {
|
||||
return false;
|
||||
}
|
||||
addr[i] = v;
|
||||
s = strtok_r(nullptr, ":", &ptr);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
int32_t AP_Networking::send_udp(struct udp_pcb *pcb, const ip4_addr_t &ip4_addr, const uint16_t port, const uint8_t* data, uint16_t data_len)
|
||||
{
|
||||
|
|
|
@ -17,9 +17,11 @@
|
|||
#define IP4_ADDR_VALUE(a,b,c,d) be32toh(UINT32_VALUE(a,b,c,d))
|
||||
#endif
|
||||
|
||||
#define IP4_ADDR_VALUE_FROM_ARRAY(array) IP4_ADDR_VALUE(array[0],array[1],array[2],array[3])
|
||||
#define IP4_ADDR_FROM_ARRAY(dest_ip, array) IP4_ADDR(dest_ip, array[0],array[1],array[2],array[3])
|
||||
#define IP_ADDR_FROM_ARRAY(dest_ip, array) IP4_ADDR_FROM_ARRAY(dest_ip, array)
|
||||
#include "AP_Networking_address.h"
|
||||
|
||||
/*
|
||||
Note! all uint32_t IPv4 addresses are in network byte order (big-endian)
|
||||
*/
|
||||
|
||||
class AP_Networking
|
||||
{
|
||||
|
@ -67,35 +69,22 @@ public:
|
|||
// returns the 32bit value of the user-parameter static IP address
|
||||
uint32_t get_ip_param() const
|
||||
{
|
||||
return IP4_ADDR_VALUE_FROM_ARRAY(_param.ipaddr);
|
||||
return _param.ipaddr.get_uint32();
|
||||
}
|
||||
|
||||
// returns a null terminated string of the active IP address. Example: "192.168.12.13"
|
||||
const char* get_ip_active_str() const
|
||||
/*
|
||||
returns a null terminated string of the active IP address. Example: "192.168.12.13"
|
||||
Note that the returned
|
||||
*/
|
||||
const char *get_ip_active_str() const
|
||||
{
|
||||
return convert_ip_to_str(get_ip_active());
|
||||
}
|
||||
|
||||
// returns a null terminated string of the user-parameter static IP address. Example: "192.168.12.13"
|
||||
const char* get_ip_param_str() const
|
||||
{
|
||||
return convert_ip_to_str(get_ip_param());
|
||||
}
|
||||
|
||||
// sets the user-parameter static IP address from a null terminated string.
|
||||
void set_ip_param_str(const char* ip_str)
|
||||
{
|
||||
set_ip_param(convert_str_to_ip((char*)ip_str));
|
||||
}
|
||||
|
||||
// sets the user-parameter static IP address from a 32bit value
|
||||
void set_ip_param(const uint32_t ip)
|
||||
void set_ip_param(const uint32_t ip)
|
||||
{
|
||||
//put_le32_ptr(_param.ipaddr->get(), ip);
|
||||
_param.ipaddr[3].set_and_save((ip >> 24) & 0xff);
|
||||
_param.ipaddr[2].set_and_save((ip >> 16) & 0xff);
|
||||
_param.ipaddr[1].set_and_save((ip >> 8) & 0xff);
|
||||
_param.ipaddr[0].set_and_save(ip & 0xff);
|
||||
_param.ipaddr.set_uint32(ip);
|
||||
}
|
||||
|
||||
// returns the 32bit value of the active Netmask that is currently in use
|
||||
|
@ -111,19 +100,22 @@ public:
|
|||
}
|
||||
|
||||
// returns a null terminated string of the active Netmask address. Example: "192.168.12.13"
|
||||
const char* get_netmask_active_str()
|
||||
const char *get_netmask_active_str()
|
||||
{
|
||||
return convert_ip_to_str(get_netmask_active());
|
||||
}
|
||||
const char* get_netmask_param_str()
|
||||
|
||||
const char *get_netmask_param_str()
|
||||
{
|
||||
return convert_ip_to_str(get_netmask_param());
|
||||
}
|
||||
void set_netmask_param_str(const char* nm_str)
|
||||
|
||||
void set_netmask_param_str(const char* nm_str)
|
||||
{
|
||||
set_netmask_param(convert_str_to_ip((char*)nm_str));
|
||||
}
|
||||
void set_netmask_param(const uint32_t nm)
|
||||
|
||||
void set_netmask_param(const uint32_t nm)
|
||||
{
|
||||
_param.netmask.set(convert_netmask_ip_to_bitcount(nm));
|
||||
}
|
||||
|
@ -132,37 +124,41 @@ public:
|
|||
{
|
||||
return _activeSettings.gw;
|
||||
}
|
||||
|
||||
uint32_t get_gateway_param() const
|
||||
{
|
||||
return IP4_ADDR_VALUE_FROM_ARRAY(_param.gwaddr);
|
||||
return _param.gwaddr.get_uint32();
|
||||
}
|
||||
const char* get_gateway_active_str()
|
||||
|
||||
const char *get_gateway_active_str()
|
||||
{
|
||||
return convert_ip_to_str(get_gateway_active());
|
||||
}
|
||||
const char* get_gateway_param_str()
|
||||
|
||||
const char *get_gateway_param_str()
|
||||
{
|
||||
return convert_ip_to_str(get_gateway_param());
|
||||
}
|
||||
void set_gateway_param_str(const char* gw_str)
|
||||
|
||||
void set_gateway_param_str(const char* gw_str)
|
||||
{
|
||||
set_gateway_param(convert_str_to_ip((char*)gw_str));
|
||||
}
|
||||
void set_gateway_param(const uint32_t gw)
|
||||
|
||||
void set_gateway_param(const uint32_t gw)
|
||||
{
|
||||
//put_le32_ptr(_param.gwaddr->get(), gw);
|
||||
_param.gwaddr[3].set_and_save((gw >> 24) & 0xff);
|
||||
_param.gwaddr[2].set_and_save((gw >> 16) & 0xff);
|
||||
_param.gwaddr[1].set_and_save((gw >> 8) & 0xff);
|
||||
_param.gwaddr[0].set_and_save(gw & 0xff);
|
||||
_param.gwaddr.set_uint32(gw);
|
||||
}
|
||||
|
||||
|
||||
// helper functions to convert between 32bit IP addresses and null terminated strings and back
|
||||
static uint32_t convert_str_to_ip(char* ip_str);
|
||||
static uint32_t convert_str_to_ip(const char* ip_str);
|
||||
static const char* convert_ip_to_str(const uint8_t ip[4]);
|
||||
static const char* convert_ip_to_str(const uint32_t ip);
|
||||
|
||||
// convert string to ethernet mac address
|
||||
static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]);
|
||||
|
||||
// helper functions to convert between 32bit Netmask and counting consecutive bits and back
|
||||
static uint32_t convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount);
|
||||
static uint8_t convert_netmask_ip_to_bitcount(const uint32_t netmask_ip);
|
||||
|
@ -186,12 +182,12 @@ private:
|
|||
} _init;
|
||||
|
||||
struct {
|
||||
AP_Int16 ipaddr[4];
|
||||
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_Int16 gwaddr[4];
|
||||
AP_Networking_IPV4 gwaddr{AP_NETWORKING_DEFAULT_STATIC_GW_ADDR};
|
||||
|
||||
AP_Int8 dhcp;
|
||||
AP_Int16 macaddr[6];
|
||||
AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR};
|
||||
AP_Int8 enabled;
|
||||
AP_Int32 options;
|
||||
} _param;
|
||||
|
@ -201,8 +197,10 @@ private:
|
|||
uint32_t nm;
|
||||
uint32_t gw;
|
||||
uint32_t announce_ms;
|
||||
uint8_t macaddr[6];
|
||||
bool announce_at_boot_done;
|
||||
} _activeSettings;
|
||||
struct lwipthread_opts lwip_options;
|
||||
|
||||
HAL_Semaphore _sem;
|
||||
};
|
||||
|
|
|
@ -20,18 +20,9 @@
|
|||
#define AP_NETWORKING_DEFAULT_DHCP_ENABLE 1
|
||||
#endif
|
||||
|
||||
// Default Static IP Address: 192.168.13.13
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR0
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR0 192
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR1
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR1 168
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR2
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR2 13
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR3
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR3 14
|
||||
// Default Static IP Address: 192.168.13.14
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR "192.168.13.14"
|
||||
#endif
|
||||
|
||||
// Default Netmask: 24
|
||||
|
@ -43,38 +34,12 @@
|
|||
|
||||
|
||||
// Default Static IP Address: 192.168.13.1
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR0
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR0 192
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR1
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR1 168
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR2
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR2 13
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR3
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR3 1
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR "192.168.13.1"
|
||||
#endif
|
||||
|
||||
|
||||
// Default MAC Address: 2C:AF:51:03:CF:46
|
||||
// Default MAC Address: C2:AF:51:03:CF:46
|
||||
// Note, lower 3 bytes (ADDR3,4,5) will be replaced with the platform UUID
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR0
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR0 0xC2 //LWIP_ETHADDR_0
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46"
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR1
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR1 0xAF //LWIP_ETHADDR_1
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR2
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR2 0x51 //LWIP_ETHADDR_2
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR3
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR3 0x03 //LWIP_ETHADDR_3
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR4
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR4 0xCF //LWIP_ETHADDR_4
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR5
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR5 0x46 //LWIP_ETHADDR_5
|
||||
#endif
|
||||
|
||||
|
|
|
@ -0,0 +1,152 @@
|
|||
/*
|
||||
classes for holding IPv4 and ethernet MAC address parameters
|
||||
*/
|
||||
|
||||
#include "AP_Networking_Config.h"
|
||||
|
||||
#if AP_NETWORKING_ENABLED
|
||||
|
||||
#include "AP_Networking.h"
|
||||
|
||||
const AP_Param::GroupInfo AP_Networking_IPV4::var_info[] = {
|
||||
// @Param: 0
|
||||
// @DisplayName: IPv4 Address 1st byte
|
||||
// @Description: IPv4 address. Example: 192.xxx.xxx.xxx
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("0", 1, AP_Networking_IPV4, addr[0], 0),
|
||||
|
||||
// @Param: 1
|
||||
// @DisplayName: IPv4 Address MSB
|
||||
// @Description: IPv4 address. Example: xxx.168.xxx.xxx
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("1", 2, AP_Networking_IPV4, addr[1], 0),
|
||||
|
||||
// @Param: 2
|
||||
// @DisplayName: IPv4 Address MSB
|
||||
// @Description: IPv4 address. Example: xxx.xxx.13.xxx
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("2", 3, AP_Networking_IPV4, addr[2], 0),
|
||||
|
||||
// @Param: 3
|
||||
// @DisplayName: IPv4 Address MSB
|
||||
// @Description: IPv4 address. Example: xxx.xxx.xxx.14
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("3", 4, AP_Networking_IPV4, addr[3], 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
const AP_Param::GroupInfo AP_Networking_MAC::var_info[] = {
|
||||
// @Param: 0
|
||||
// @DisplayName: MAC Address 1st byte
|
||||
// @Description: MAC address 1st byte
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("0", 1, AP_Networking_MAC, addr[0], 0),
|
||||
|
||||
// @Param: 1
|
||||
// @DisplayName: MAC Address 2nd byte
|
||||
// @Description: MAC address 2nd byte
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("1", 2, AP_Networking_MAC, addr[1], 0),
|
||||
|
||||
// @Param: 2
|
||||
// @DisplayName: MAC Address 3rd byte
|
||||
// @Description: MAC address 3rd byte
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2", 3, AP_Networking_MAC, addr[2], 0),
|
||||
|
||||
// @Param: 3
|
||||
// @DisplayName: MAC Address 4th byte
|
||||
// @Description: MAC address 4th byte
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("3", 4, AP_Networking_MAC, addr[3], 0),
|
||||
|
||||
// @Param: 4
|
||||
// @DisplayName: MAC Address 5th byte
|
||||
// @Description: MAC address 5th byte
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("4", 5, AP_Networking_MAC, addr[4], 0),
|
||||
|
||||
// @Param: 5
|
||||
// @DisplayName: MAC Address 6th byte
|
||||
// @Description: MAC address 6th byte
|
||||
// @Range: 0 255
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("5", 6, AP_Networking_MAC, addr[5], 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
||||
|
||||
/*
|
||||
IPV4 address parameter class
|
||||
*/
|
||||
AP_Networking_IPV4::AP_Networking_IPV4(const char *default_addr)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
set_default_uint32(AP_Networking::convert_str_to_ip(default_addr));
|
||||
}
|
||||
|
||||
uint32_t AP_Networking_IPV4::get_uint32(void) const
|
||||
{
|
||||
uint32_t v = 0;
|
||||
uint8_t *b = (uint8_t*)&v;
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(addr); i++) {
|
||||
b[i] = uint8_t(addr[i].get());
|
||||
}
|
||||
return v;
|
||||
}
|
||||
|
||||
void AP_Networking_IPV4::set_default_uint32(uint32_t v)
|
||||
{
|
||||
uint8_t *b = (uint8_t*)&v;
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(addr); i++) {
|
||||
addr[i].set_default(b[i]);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
ethernet MAC address parameter class
|
||||
*/
|
||||
AP_Networking_MAC::AP_Networking_MAC(const char *default_addr)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
uint8_t b[6];
|
||||
if (AP_Networking::convert_str_to_macaddr(default_addr, b)) {
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(addr); i++) {
|
||||
addr[i].set_default(b[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Networking_MAC::get_address(uint8_t v[6]) const
|
||||
{
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(addr); i++) {
|
||||
v[i] = uint8_t(addr[i].get());
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Networking_MAC::set_default_address_byte(uint8_t idx, uint8_t b)
|
||||
{
|
||||
if (idx < ARRAY_SIZE(addr)) {
|
||||
addr[idx].set_default(b);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // AP_NETWORKING_ENABLED
|
|
@ -0,0 +1,36 @@
|
|||
#pragma once
|
||||
|
||||
/*
|
||||
class for an IPV4 address as a parameter
|
||||
*/
|
||||
class AP_Networking_IPV4
|
||||
{
|
||||
public:
|
||||
AP_Networking_IPV4(const char *default_addr);
|
||||
AP_Int16 addr[4];
|
||||
|
||||
// return address as a uint32_t
|
||||
uint32_t get_uint32(void) const;
|
||||
|
||||
// set address from a uint32_t
|
||||
void set_uint32(uint32_t addr);
|
||||
|
||||
// set default address from a uint32
|
||||
void set_default_uint32(uint32_t addr);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
};
|
||||
|
||||
/*
|
||||
class for an ethernet MAC address as a parameter
|
||||
*/
|
||||
class AP_Networking_MAC
|
||||
{
|
||||
public:
|
||||
AP_Networking_MAC(const char *default_addr);
|
||||
AP_Int16 addr[6];
|
||||
void get_address(uint8_t addr[6]) const;
|
||||
void set_default_address_byte(uint8_t idx, uint8_t b);
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
};
|
||||
|
Loading…
Reference in New Issue