AP_Networking: astyle changes
This commit is contained in:
parent
90dc58be29
commit
1aff011e52
@ -7,12 +7,12 @@
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
#include <hal_mii.h>
|
||||
#include <lwip/sockets.h>
|
||||
#include <hal_mii.h>
|
||||
#include <lwip/sockets.h>
|
||||
#else
|
||||
#include <arpa/inet.h>
|
||||
#include <sys/socket.h>
|
||||
|
||||
#include <arpa/inet.h>
|
||||
#include <sys/socket.h>
|
||||
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -203,11 +203,12 @@ void AP_Networking::init()
|
||||
(uint8_t)_param.macaddr[2].get(),
|
||||
(uint8_t)_param.macaddr[3].get(),
|
||||
(uint8_t)_param.macaddr[4].get(),
|
||||
(uint8_t)_param.macaddr[5].get() };
|
||||
(uint8_t)_param.macaddr[5].get()
|
||||
};
|
||||
|
||||
#if !AP_NETWORKING_DHCP_AVAILABLE
|
||||
set_dhcp_enable(false);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: DHCP Not Supported");
|
||||
set_dhcp_enable(false);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: DHCP Not Supported");
|
||||
#endif
|
||||
|
||||
net_addr_mode_t addrMode;
|
||||
@ -224,10 +225,11 @@ void AP_Networking::init()
|
||||
}
|
||||
|
||||
struct lwipthread_opts netOptions = { (uint8_t *) localMACAddress,
|
||||
_activeSettings.ip,
|
||||
_activeSettings.nm,
|
||||
_activeSettings.gw,
|
||||
addrMode };
|
||||
_activeSettings.ip,
|
||||
_activeSettings.nm,
|
||||
_activeSettings.gw,
|
||||
addrMode
|
||||
};
|
||||
|
||||
lwipInit(&netOptions);
|
||||
#endif
|
||||
@ -268,8 +270,7 @@ void AP_Networking::announce_address_changes()
|
||||
if (_activeSettings.announce_at_boot_done &&
|
||||
ip == _activeSettings.ip &&
|
||||
nm == _activeSettings.nm &&
|
||||
gw == _activeSettings.gw)
|
||||
{
|
||||
gw == _activeSettings.gw) {
|
||||
// nothing changed and we've already printed it at least once. Nothing to do.
|
||||
return;
|
||||
}
|
||||
@ -343,10 +344,10 @@ char* AP_Networking::convert_ip_to_str(const uint8_t ip[4])
|
||||
char* AP_Networking::convert_ip_to_str(const uint32_t ip)
|
||||
{
|
||||
uint8_t ip_array[4];
|
||||
ip_array[3] = ((ip >> 24) & 0xff);
|
||||
ip_array[2] = ((ip >> 16) & 0xff);
|
||||
ip_array[1] = ((ip >> 8) & 0xff);
|
||||
ip_array[0] = (ip & 0xff);
|
||||
ip_array[3] = ((ip >> 24) & 0xff);
|
||||
ip_array[2] = ((ip >> 16) & 0xff);
|
||||
ip_array[1] = ((ip >> 8) & 0xff);
|
||||
ip_array[0] = (ip & 0xff);
|
||||
|
||||
return convert_ip_to_str(ip_array);
|
||||
}
|
||||
@ -361,7 +362,7 @@ int32_t AP_Networking::send_udp(struct udp_pcb *pcb, const ip4_addr_t &ip4_addr,
|
||||
if (pcb == nullptr) {
|
||||
return ERR_ARG;
|
||||
}
|
||||
|
||||
|
||||
data_len = (data == nullptr) ? 0 : data_len;
|
||||
|
||||
struct pbuf *p = pbuf_alloc(PBUF_TRANSPORT, data_len, PBUF_RAM);
|
||||
@ -384,10 +385,12 @@ int32_t AP_Networking::send_udp(struct udp_pcb *pcb, const ip4_addr_t &ip4_addr,
|
||||
#endif // #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
||||
AP_Networking *AP_Networking::_singleton;
|
||||
namespace AP {
|
||||
AP_Networking &network() {
|
||||
return *AP_Networking::get_singleton();
|
||||
}
|
||||
namespace AP
|
||||
{
|
||||
AP_Networking &network()
|
||||
{
|
||||
return *AP_Networking::get_singleton();
|
||||
}
|
||||
}
|
||||
|
||||
#endif // AP_NETWORKING_ENABLED
|
||||
|
@ -9,12 +9,12 @@
|
||||
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
#include "lwipthread.h"
|
||||
#include "lwip/udp.h"
|
||||
#include <lwip/ip_addr.h>
|
||||
#include "lwipthread.h"
|
||||
#include "lwip/udp.h"
|
||||
#include <lwip/ip_addr.h>
|
||||
#else
|
||||
#include <AP_Common/missing/byteswap.h>
|
||||
#define IP4_ADDR_VALUE(a,b,c,d) be32toh(UINT32_VALUE(a,b,c,d))
|
||||
#include <AP_Common/missing/byteswap.h>
|
||||
#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])
|
||||
@ -33,44 +33,106 @@ public:
|
||||
|
||||
void update();
|
||||
|
||||
static AP_Networking *get_singleton(void) { return _singleton; }
|
||||
static AP_Networking *get_singleton(void)
|
||||
{
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
bool is_healthy() const { return _param.enabled && _init.done; }
|
||||
bool get_dhcp_enabled() const { return _param.dhcp; }
|
||||
void set_dhcp_enable(const bool enable) { _param.dhcp.set(enable); }
|
||||
bool is_healthy() const
|
||||
{
|
||||
return _param.enabled && _init.done;
|
||||
}
|
||||
bool get_dhcp_enabled() const
|
||||
{
|
||||
return _param.dhcp;
|
||||
}
|
||||
void set_dhcp_enable(const bool enable)
|
||||
{
|
||||
_param.dhcp.set(enable);
|
||||
}
|
||||
|
||||
uint32_t get_ip_active() const { return _activeSettings.ip; }
|
||||
uint32_t get_ip_param() const { return IP4_ADDR_VALUE_FROM_ARRAY(_param.ipaddr); }
|
||||
char* get_ip_active_str() const { return convert_ip_to_str(get_ip_active()); }
|
||||
char* get_ip_param_str() const { return convert_ip_to_str(get_ip_param()); }
|
||||
void set_ip_param_str(const char* ip_str) { set_ip_param(convert_str_to_ip((char*)ip_str)); }
|
||||
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);
|
||||
}
|
||||
uint32_t get_ip_active() const
|
||||
{
|
||||
return _activeSettings.ip;
|
||||
}
|
||||
uint32_t get_ip_param() const
|
||||
{
|
||||
return IP4_ADDR_VALUE_FROM_ARRAY(_param.ipaddr);
|
||||
}
|
||||
char* get_ip_active_str() const
|
||||
{
|
||||
return convert_ip_to_str(get_ip_active());
|
||||
}
|
||||
char* get_ip_param_str() const
|
||||
{
|
||||
return convert_ip_to_str(get_ip_param());
|
||||
}
|
||||
void set_ip_param_str(const char* ip_str)
|
||||
{
|
||||
set_ip_param(convert_str_to_ip((char*)ip_str));
|
||||
}
|
||||
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);
|
||||
}
|
||||
|
||||
uint32_t get_netmask_active() const { return _activeSettings.nm; }
|
||||
uint32_t get_netmask_param() const { return convert_netmask_bitcount_to_ip(_param.netmask.get()); }
|
||||
char* get_netmask_active_str() { return convert_ip_to_str(get_netmask_active()); }
|
||||
char* get_netmask_param_str() { return convert_ip_to_str(get_netmask_param()); }
|
||||
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) { _param.netmask.set(convert_netmask_ip_to_bitcount(nm)); }
|
||||
uint32_t get_netmask_active() const
|
||||
{
|
||||
return _activeSettings.nm;
|
||||
}
|
||||
uint32_t get_netmask_param() const
|
||||
{
|
||||
return convert_netmask_bitcount_to_ip(_param.netmask.get());
|
||||
}
|
||||
char* get_netmask_active_str()
|
||||
{
|
||||
return convert_ip_to_str(get_netmask_active());
|
||||
}
|
||||
char* get_netmask_param_str()
|
||||
{
|
||||
return convert_ip_to_str(get_netmask_param());
|
||||
}
|
||||
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)
|
||||
{
|
||||
_param.netmask.set(convert_netmask_ip_to_bitcount(nm));
|
||||
}
|
||||
|
||||
uint32_t get_gateway_active() const { return _activeSettings.gw; }
|
||||
uint32_t get_gateway_param() const { return IP4_ADDR_VALUE_FROM_ARRAY(_param.gwaddr); }
|
||||
char* get_gateway_active_str() { return convert_ip_to_str(get_gateway_active()); }
|
||||
char* get_gateway_param_str() { return convert_ip_to_str(get_gateway_param()); }
|
||||
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) {
|
||||
//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);
|
||||
}
|
||||
uint32_t get_gateway_active() const
|
||||
{
|
||||
return _activeSettings.gw;
|
||||
}
|
||||
uint32_t get_gateway_param() const
|
||||
{
|
||||
return IP4_ADDR_VALUE_FROM_ARRAY(_param.gwaddr);
|
||||
}
|
||||
char* get_gateway_active_str()
|
||||
{
|
||||
return convert_ip_to_str(get_gateway_active());
|
||||
}
|
||||
char* get_gateway_param_str()
|
||||
{
|
||||
return convert_ip_to_str(get_gateway_param());
|
||||
}
|
||||
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)
|
||||
{
|
||||
//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);
|
||||
}
|
||||
|
||||
|
||||
static uint32_t convert_str_to_ip(char* ip_str);
|
||||
@ -107,7 +169,7 @@ private:
|
||||
AP_Int8 dhcp;
|
||||
AP_Int16 macaddr[6];
|
||||
AP_Int8 enabled;
|
||||
AP_Int32 options;
|
||||
AP_Int32 options;
|
||||
} _param;
|
||||
|
||||
struct {
|
||||
@ -121,8 +183,9 @@ private:
|
||||
HAL_Semaphore _sem;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
AP_Networking &network();
|
||||
namespace AP
|
||||
{
|
||||
AP_Networking &network();
|
||||
};
|
||||
|
||||
#endif // AP_NETWORKING_ENABLED
|
||||
|
@ -5,9 +5,9 @@
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
#define AP_NETWORKING_DHCP_AVAILABLE LWIP_DHCP
|
||||
#define AP_NETWORKING_DHCP_AVAILABLE LWIP_DHCP
|
||||
#else
|
||||
#define AP_NETWORKING_DHCP_AVAILABLE 1 // for non-ChibiOS, assume it's available
|
||||
#define AP_NETWORKING_DHCP_AVAILABLE 1 // for non-ChibiOS, assume it's available
|
||||
#endif
|
||||
|
||||
|
||||
@ -22,59 +22,59 @@
|
||||
|
||||
// Default Static IP Address: 192.168.13.13
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR0
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR0 192
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR0 192
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR1
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR1 168
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR1 168
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR2
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR2 13
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR2 13
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR3
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR3 14
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR3 14
|
||||
#endif
|
||||
|
||||
// Default Netmask: 24
|
||||
// Note, the netmask is the number of consecutive bits
|
||||
#ifndef AP_NETWORKING_DEFAULT_NETMASK
|
||||
#define AP_NETWORKING_DEFAULT_NETMASK 24 // 255.255.255.0 (for 10.0.xxx.xxx or 172.xxx.xxx.xxx type networks)
|
||||
// #define AP_NETWORKING_DEFAULT_NETMASK 16 // 255.255.0.0 (for 192.168.xxx.xxxx type networks)
|
||||
#define AP_NETWORKING_DEFAULT_NETMASK 24 // 255.255.255.0 (for 10.0.xxx.xxx or 172.xxx.xxx.xxx type networks)
|
||||
// #define AP_NETWORKING_DEFAULT_NETMASK 16 // 255.255.0.0 (for 192.168.xxx.xxxx type networks)
|
||||
#endif
|
||||
|
||||
|
||||
// Default Static IP Address: 192.168.13.1
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR0
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR0 192
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR0 192
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR1
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR1 168
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR1 168
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR2
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR2 13
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR2 13
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR3
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR3 1
|
||||
#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR3 1
|
||||
#endif
|
||||
|
||||
|
||||
// Default MAC Address: 2C:AF:51:03:CF:46
|
||||
// Note, lower 3 bytes (ADDR3,4,5) will be replaced with the platform UUID
|
||||
// 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
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR0 0xC2 //LWIP_ETHADDR_0
|
||||
#endif
|
||||
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR1
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR1 0xAF //LWIP_ETHADDR_1
|
||||
#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
|
||||
#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
|
||||
#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
|
||||
#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
|
||||
#define AP_NETWORKING_DEFAULT_MAC_ADDR5 0x46 //LWIP_ETHADDR_5
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user