AP_Networking: use host byte order addresses internally

this should make the lua API easier to handle, as it can manipulate
uint32_t easily
This commit is contained in:
Andrew Tridgell 2023-08-05 17:08:52 +10:00
parent 8ddaf17184
commit 5af7fdf330
4 changed files with 18 additions and 37 deletions

View File

@ -142,14 +142,10 @@ void AP_Networking::update()
uint32_t AP_Networking::convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount)
{
if (netmask_bitcount > 32) {
return 0;
if (netmask_bitcount >= 32) {
return 0xFFFFFFFFU;
}
uint32_t netmask_ip = 0;
for (uint32_t i=0; i<netmask_bitcount; i++) {
netmask_ip |= (1UL << i);
}
return netmask_ip;
return ~((1U<<(32U-netmask_bitcount))-1U);
}
uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip)
@ -169,29 +165,17 @@ uint32_t AP_Networking::convert_str_to_ip(const char* ip_str)
{
uint32_t ip = 0;
inet_pton(AF_INET, ip_str, &ip);
return ip;
return ntohl(ip);
}
const char* AP_Networking::convert_ip_to_str(const uint8_t ip[4])
const char* AP_Networking::convert_ip_to_str(uint32_t ip)
{
ip = htonl(ip);
static char _str_buffer[20];
if (hal.util->snprintf(_str_buffer, sizeof(_str_buffer), "%u.%u.%u.%u", (unsigned)ip[0], (unsigned)ip[1], (unsigned)ip[2], (unsigned)ip[3]) == 0) {
_str_buffer[0] = '\0';
}
inet_ntop(AF_INET, &ip, _str_buffer, sizeof(_str_buffer));
return _str_buffer;
}
const 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);
return convert_ip_to_str(ip_array);
}
/*
convert a string to an ethernet MAC address
*/

View File

@ -11,7 +11,7 @@
#include "AP_Networking_backend.h"
/*
Note! all uint32_t IPv4 addresses are in network byte order (big-endian)
Note! all uint32_t IPv4 addresses are in host byte order
*/
class AP_Networking
@ -145,8 +145,7 @@ public:
// helper functions to convert between 32bit IP addresses and null terminated strings and back
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);
static const char* convert_ip_to_str(uint32_t ip);
// convert string to ethernet mac address
static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]);

View File

@ -114,9 +114,9 @@ bool AP_Networking_ChibiOS::init()
lwip_options->addrMode = NET_ADDRESS_DHCP;
} else {
lwip_options->addrMode = NET_ADDRESS_STATIC;
lwip_options->address = frontend.get_ip_param();
lwip_options->netmask = frontend.get_netmask_param();
lwip_options->gateway = frontend.get_gateway_param();
lwip_options->address = htonl(frontend.get_ip_param());
lwip_options->netmask = htonl(frontend.get_netmask_param());
lwip_options->gateway = htonl(frontend.get_gateway_param());
}
frontend.param.macaddr.get_address(macaddr);
lwip_options->macaddress = macaddr;
@ -131,9 +131,9 @@ bool AP_Networking_ChibiOS::init()
*/
void AP_Networking_ChibiOS::update()
{
const uint32_t ip = lwipGetIp();
const uint32_t nm = lwipGetNetmask();
const uint32_t gw = lwipGetGateway();
const uint32_t ip = ntohl(lwipGetIp());
const uint32_t nm = ntohl(lwipGetNetmask());
const uint32_t gw = ntohl(lwipGetGateway());
if (ip != activeSettings.ip ||
nm != activeSettings.nm ||

View File

@ -92,8 +92,6 @@ const AP_Param::GroupInfo AP_Networking_MAC::var_info[] = {
AP_GROUPEND
};
/*
IPV4 address parameter class
*/
@ -107,8 +105,8 @@ 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());
for (uint8_t i=0; i<4; i++) {
b[3-i] = uint8_t(addr[i].get());
}
return v;
}
@ -117,7 +115,7 @@ 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]);
addr[3-i].set_default(b[i]);
}
}