mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Networking: cleanup string to IP handling
use SocketAPM methods
This commit is contained in:
parent
3d5251dfe8
commit
ec5ff94f3e
@ -19,7 +19,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
#include <lwipopts.h>
|
#include <lwipopts.h>
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
#include <lwip/sockets.h>
|
|
||||||
|
|
||||||
|
|
||||||
#include <AP_HAL/utility/Socket.h>
|
#include <AP_HAL/utility/Socket.h>
|
||||||
@ -183,9 +182,10 @@ void AP_Networking::announce_address_changes()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", get_ip_active_str());
|
char ipstr[16];
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", get_netmask_active_str());
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", SocketAPM::inet_addr_to_str(get_ip_active(), ipstr, sizeof(ipstr)));
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", get_gateway_active_str());
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", SocketAPM::inet_addr_to_str(get_netmask_active(), ipstr, sizeof(ipstr)));
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", SocketAPM::inet_addr_to_str(get_gateway_active(), ipstr, sizeof(ipstr)));
|
||||||
|
|
||||||
announce_ms = as.last_change_ms;
|
announce_ms = as.last_change_ms;
|
||||||
}
|
}
|
||||||
@ -223,21 +223,6 @@ uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip)
|
|||||||
return netmask_bitcount;
|
return netmask_bitcount;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t AP_Networking::convert_str_to_ip(const char* ip_str)
|
|
||||||
{
|
|
||||||
uint32_t ip = 0;
|
|
||||||
lwip_inet_pton(AF_INET, ip_str, &ip);
|
|
||||||
return ntohl(ip);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char* AP_Networking::convert_ip_to_str(uint32_t ip)
|
|
||||||
{
|
|
||||||
ip = htonl(ip);
|
|
||||||
static char _str_buffer[20];
|
|
||||||
lwip_inet_ntop(AF_INET, &ip, _str_buffer, sizeof(_str_buffer));
|
|
||||||
return _str_buffer;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
convert a string to an ethernet MAC address
|
convert a string to an ethernet MAC address
|
||||||
*/
|
*/
|
||||||
|
@ -91,15 +91,6 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
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());
|
|
||||||
}
|
|
||||||
|
|
||||||
// sets the user-parameter static IP address from a 32bit value
|
// 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)
|
||||||
{
|
{
|
||||||
@ -122,29 +113,6 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns a null terminated string of the active Netmask address. Example: "192.168.12.13"
|
|
||||||
const char *get_netmask_active_str()
|
|
||||||
{
|
|
||||||
return convert_ip_to_str(get_netmask_active());
|
|
||||||
}
|
|
||||||
|
|
||||||
const 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)
|
|
||||||
{
|
|
||||||
#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_active() const;
|
||||||
|
|
||||||
uint32_t get_gateway_param() const
|
uint32_t get_gateway_param() const
|
||||||
@ -157,21 +125,6 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
const char *get_gateway_active_str()
|
|
||||||
{
|
|
||||||
return convert_ip_to_str(get_gateway_active());
|
|
||||||
}
|
|
||||||
|
|
||||||
const 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)
|
void set_gateway_param(const uint32_t gw)
|
||||||
{
|
{
|
||||||
#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED
|
#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED
|
||||||
@ -182,10 +135,6 @@ public:
|
|||||||
// wait in a thread for network startup
|
// wait in a thread for network startup
|
||||||
void startup_wait(void) const;
|
void startup_wait(void) const;
|
||||||
|
|
||||||
// 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(uint32_t ip);
|
|
||||||
|
|
||||||
// convert string to ethernet mac address
|
// convert string to ethernet mac address
|
||||||
static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]);
|
static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]);
|
||||||
|
|
||||||
|
@ -49,7 +49,7 @@ const AP_Param::GroupInfo AP_Networking_IPV4::var_info[] = {
|
|||||||
AP_Networking_IPV4::AP_Networking_IPV4(const char *default_addr)
|
AP_Networking_IPV4::AP_Networking_IPV4(const char *default_addr)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
set_default_uint32(AP_Networking::convert_str_to_ip(default_addr));
|
set_default_uint32(SocketAPM::inet_str_to_addr(default_addr));
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t AP_Networking_IPV4::get_uint32(void) const
|
uint32_t AP_Networking_IPV4::get_uint32(void) const
|
||||||
@ -73,7 +73,7 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v)
|
|||||||
const char* AP_Networking_IPV4::get_str()
|
const char* AP_Networking_IPV4::get_str()
|
||||||
{
|
{
|
||||||
const auto ip = ntohl(get_uint32());
|
const auto ip = ntohl(get_uint32());
|
||||||
return SocketAPM::inet_addr_to_str(&ip, strbuf, sizeof(strbuf));
|
return SocketAPM::inet_addr_to_str(ip, strbuf, sizeof(strbuf));
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_NETWORKING_ENABLED
|
#endif // AP_NETWORKING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user