ardupilot/libraries/AP_Networking/AP_Networking.cpp

257 lines
6.5 KiB
C++
Raw Normal View History

2023-07-06 14:46:33 -03:00
2023-08-02 21:53:32 -03:00
#include "AP_Networking_Config.h"
2023-07-06 14:46:33 -03:00
#if AP_NETWORKING_ENABLED
2023-08-02 21:53:32 -03:00
#include "AP_Networking.h"
#include "AP_Networking_Backend.h"
2023-07-06 14:46:33 -03:00
#include <GCS_MAVLink/GCS.h>
#include <AP_Math/crc.h>
2023-07-06 14:46:33 -03:00
extern const AP_HAL::HAL& hal;
2023-11-12 18:09:58 -04:00
#if AP_NETWORKING_BACKEND_CHIBIOS
#include "AP_Networking_ChibiOS.h"
2023-07-07 15:15:26 -03:00
#include <hal_mii.h>
#include <lwip/sockets.h>
2023-07-06 14:46:33 -03:00
#else
2023-07-07 15:15:26 -03:00
#include <arpa/inet.h>
2023-07-06 14:46:33 -03:00
#endif
2023-07-06 14:46:33 -03:00
const AP_Param::GroupInfo AP_Networking::var_info[] = {
// @Param: ENABLED
2023-08-02 21:53:32 -03:00
// @DisplayName: Networking Enable
// @Description: Networking Enable
2023-07-06 14:46:33 -03:00
// @Values: 0:Disable,1:Enable
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO_FLAGS("ENABLED", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE),
2023-07-06 14:46:33 -03:00
// @Group: IPADDR
// @Path: AP_Networking_address.cpp
AP_SUBGROUPINFO(param.ipaddr, "IPADDR", 2, AP_Networking, AP_Networking_IPV4),
2023-07-06 14:46:33 -03:00
// @Param: NETMASK
// @DisplayName: IP Subnet mask
// @Description: Allows setting static subnet mask. The value is a count of consecutive bits. Examples: 24 = 255.255.255.0, 16 = 255.255.0.0
// @Range: 0 32
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("NETMASK", 3, AP_Networking, param.netmask, AP_NETWORKING_DEFAULT_NETMASK),
2023-07-06 14:46:33 -03:00
// @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),
2023-07-06 14:46:33 -03:00
// @Group: GWADDR
// @Path: AP_Networking_address.cpp
AP_SUBGROUPINFO(param.gwaddr, "GWADDR", 5, AP_Networking, AP_Networking_IPV4),
2023-07-06 14:46:33 -03:00
// @Group: MACADDR
// @Path: AP_Networking_macaddr.cpp
AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC),
2023-07-06 14:46:33 -03:00
#if AP_NETWORKING_TESTS_ENABLED
// @Param: TESTS
// @DisplayName: Test enable flags
// @Description: Enable/Disable networking tests
// @Bitmask: 0:UDP echo test,1:TCP echo test
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0),
#endif
2023-07-06 14:46:33 -03:00
AP_GROUPEND
};
/*
constructor
*/
2023-07-06 14:46:33 -03:00
AP_Networking::AP_Networking(void)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (singleton != nullptr) {
2023-07-06 14:46:33 -03:00
AP_HAL::panic("AP_Networking must be singleton");
}
#endif
singleton = this;
2023-07-06 14:46:33 -03:00
AP_Param::setup_object_defaults(this, var_info);
}
/*
initialise networking subsystem
*/
2023-07-06 14:46:33 -03:00
void AP_Networking::init()
{
if (!param.enabled || backend != nullptr) {
2023-07-06 14:46:33 -03:00
return;
}
// set default MAC Address as lower 3 bytes of the CRC of the UID
uint8_t uid[50];
uint8_t uid_len = sizeof(uid);
if (hal.util->get_system_id_unformatted(uid, uid_len)) {
union {
uint8_t bytes[4];
uint32_t value32;
} crc;
crc.value32 = crc_crc32(0, uid, uid_len);
param.macaddr.set_default_address_byte(3, crc.bytes[0]);
param.macaddr.set_default_address_byte(4, crc.bytes[1]);
param.macaddr.set_default_address_byte(5, crc.bytes[2]);
2023-07-06 14:46:33 -03:00
}
2023-11-12 18:09:58 -04:00
#if AP_NETWORKING_BACKEND_CHIBIOS
backend = new AP_Networking_ChibiOS(*this);
2023-07-28 17:29:33 -03:00
#endif
if (backend == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend failed");
2023-07-06 14:46:33 -03:00
return;
}
if (!backend->init()) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend init failed");
// the backend init function creates a thread which references the backend pointer; that thread may be running so don't remove the backend allocation.
backend = nullptr;
return;
2023-07-06 14:46:33 -03:00
}
announce_address_changes();
2023-07-06 14:46:33 -03:00
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized");
#if AP_NETWORKING_TESTS_ENABLED
start_tests();
#endif
2023-07-06 14:46:33 -03:00
}
/*
check if we should announce changes to IP addresses
*/
2023-07-06 14:46:33 -03:00
void AP_Networking::announce_address_changes()
{
auto &as = backend->activeSettings;
2023-07-06 14:46:33 -03:00
if (as.last_change_ms == 0 || as.last_change_ms == announce_ms) {
2023-07-06 14:46:33 -03:00
// nothing changed and we've already printed it at least once. Nothing to do.
return;
}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", get_ip_active_str());
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", get_netmask_active_str());
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", get_gateway_active_str());
announce_ms = as.last_change_ms;
2023-07-06 14:46:33 -03:00
}
/*
update called at 10Hz
*/
2023-07-06 14:46:33 -03:00
void AP_Networking::update()
{
if (!is_healthy()) {
return;
}
backend->update();
2023-07-06 14:46:33 -03:00
announce_address_changes();
}
uint32_t AP_Networking::convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount)
{
if (netmask_bitcount >= 32) {
return 0xFFFFFFFFU;
2023-07-06 14:46:33 -03:00
}
return ~((1U<<(32U-netmask_bitcount))-1U);
2023-07-06 14:46:33 -03:00
}
uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip)
{
uint32_t netmask_bitcount = 0;
for (uint32_t i=0; i<32; i++) {
// note, netmask LSB is IP MSB
if ((netmask_ip & (1UL<<i)) == 0) {
break;
}
netmask_bitcount++;
}
return netmask_bitcount;
}
uint32_t AP_Networking::convert_str_to_ip(const char* ip_str)
2023-07-06 14:46:33 -03:00
{
uint32_t ip = 0;
inet_pton(AF_INET, ip_str, &ip);
return ntohl(ip);
2023-07-06 14:46:33 -03:00
}
const char* AP_Networking::convert_ip_to_str(uint32_t ip)
2023-07-06 14:46:33 -03:00
{
ip = htonl(ip);
2023-07-06 14:46:33 -03:00
static char _str_buffer[20];
inet_ntop(AF_INET, &ip, _str_buffer, sizeof(_str_buffer));
2023-07-06 14:46:33 -03:00
return _str_buffer;
}
/*
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;
}
2023-11-12 18:09:58 -04:00
// returns the 32bit value of the active IP address that is currently in use
uint32_t AP_Networking::get_ip_active() const
{
return backend?backend->activeSettings.ip:0;
}
// returns the 32bit value of the active Netmask that is currently in use
uint32_t AP_Networking::get_netmask_active() const
{
return backend?backend->activeSettings.nm:0;
}
uint32_t AP_Networking::get_gateway_active() const
{
return backend?backend->activeSettings.gw:0;
}
AP_Networking *AP_Networking::singleton;
2023-07-06 14:46:33 -03:00
2023-07-07 15:15:26 -03:00
namespace AP
{
AP_Networking &network()
{
return *AP_Networking::get_singleton();
}
2023-07-06 14:46:33 -03:00
}
#endif // AP_NETWORKING_ENABLED