ardupilot/libraries/AP_Networking/AP_Networking.h

253 lines
6.3 KiB
C
Raw Normal View History

2023-07-06 14:46:33 -03:00
#pragma once
#include "AP_Networking_Config.h"
#if AP_NETWORKING_ENABLED
#include <AP_Param/AP_Param.h>
#include "AP_Networking_address.h"
#include "AP_Networking_Backend.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_HAL/utility/RingBuffer.h>
/*
Note! all uint32_t IPv4 addresses are in host byte order
*/
2023-07-06 14:46:33 -03:00
2023-11-12 18:09:58 -04:00
// declare backend classes
class AP_Networking_Backend;
2023-11-12 18:09:58 -04:00
class AP_Networking_ChibiOS;
class SocketAPM;
2023-07-06 14:46:33 -03:00
class AP_Networking
{
public:
friend class AP_Networking_Backend;
friend class AP_Networking_ChibiOS;
friend class AP_Vehicle;
2023-07-06 14:46:33 -03:00
AP_Networking();
/* Do not allow copies */
CLASS_NO_COPY(AP_Networking);
2023-08-02 21:53:32 -03:00
// initialize the library. This should only be run once
2023-07-06 14:46:33 -03:00
void init();
// update task, called at 10Hz
2023-07-06 14:46:33 -03:00
void update();
2023-07-07 15:15:26 -03:00
static AP_Networking *get_singleton(void)
{
return singleton;
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
// Networking interface is enabled and initialized
2023-07-07 15:15:26 -03:00
bool is_healthy() const
{
return param.enabled && backend != nullptr;
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
// returns true if DHCP is enabled
2023-07-07 15:15:26 -03:00
bool get_dhcp_enabled() const
{
return param.dhcp;
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
// Sets DHCP to be enabled or disabled
2023-07-07 15:15:26 -03:00
void set_dhcp_enable(const bool enable)
{
param.dhcp.set(enable);
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
// returns the 32bit value of the active IP address that is currently in use
2023-11-12 18:09:58 -04:00
uint32_t get_ip_active() const;
2023-08-02 21:53:32 -03:00
// returns the 32bit value of the user-parameter static IP address
2023-07-07 15:15:26 -03:00
uint32_t get_ip_param() const
{
return param.ipaddr.get_uint32();
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
/*
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
2023-07-07 15:15:26 -03:00
{
return convert_ip_to_str(get_ip_active());
}
2023-08-02 21:53:32 -03:00
// sets the user-parameter static IP address from a 32bit value
void set_ip_param(const uint32_t ip)
2023-07-07 15:15:26 -03:00
{
param.ipaddr.set_uint32(ip);
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
// returns the 32bit value of the active Netmask that is currently in use
2023-11-12 18:09:58 -04:00
uint32_t get_netmask_active() const;
2023-08-02 21:53:32 -03:00
// returns the 32bit value of the of the user-parameter static Netmask
2023-07-07 15:15:26 -03:00
uint32_t get_netmask_param() const
{
return convert_netmask_bitcount_to_ip(param.netmask.get());
2023-07-07 15:15:26 -03:00
}
2023-08-02 21:53:32 -03:00
// returns a null terminated string of the active Netmask address. Example: "192.168.12.13"
const char *get_netmask_active_str()
2023-07-07 15:15:26 -03:00
{
return convert_ip_to_str(get_netmask_active());
}
const char *get_netmask_param_str()
2023-07-07 15:15:26 -03:00
{
return convert_ip_to_str(get_netmask_param());
}
void set_netmask_param_str(const char* nm_str)
2023-07-07 15:15:26 -03:00
{
set_netmask_param(convert_str_to_ip((char*)nm_str));
}
void set_netmask_param(const uint32_t nm)
2023-07-07 15:15:26 -03:00
{
param.netmask.set(convert_netmask_ip_to_bitcount(nm));
2023-07-07 15:15:26 -03:00
}
2023-11-12 18:09:58 -04:00
uint32_t get_gateway_active() const;
2023-07-07 15:15:26 -03:00
uint32_t get_gateway_param() const
{
return param.gwaddr.get_uint32();
2023-07-07 15:15:26 -03:00
}
const char *get_gateway_active_str()
2023-07-07 15:15:26 -03:00
{
return convert_ip_to_str(get_gateway_active());
}
const char *get_gateway_param_str()
2023-07-07 15:15:26 -03:00
{
return convert_ip_to_str(get_gateway_param());
}
void set_gateway_param_str(const char* gw_str)
2023-07-07 15:15:26 -03:00
{
set_gateway_param(convert_str_to_ip((char*)gw_str));
}
void set_gateway_param(const uint32_t gw)
2023-07-07 15:15:26 -03:00
{
param.gwaddr.set_uint32(gw);
2023-07-07 15:15:26 -03:00
}
2023-07-06 14:46:33 -03:00
2023-08-02 21:53:32 -03:00
// 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);
2023-07-06 14:46:33 -03:00
// convert string to ethernet mac address
static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]);
2023-08-02 21:53:32 -03:00
// helper functions to convert between 32bit Netmask and counting consecutive bits and back
2023-07-06 14:46:33 -03:00
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);
static const struct AP_Param::GroupInfo var_info[];
private:
static AP_Networking *singleton;
2023-07-06 14:46:33 -03:00
void announce_address_changes();
struct {
AP_Networking_IPV4 ipaddr{AP_NETWORKING_DEFAULT_STATIC_IP_ADDR};
2023-07-06 14:46:33 -03:00
AP_Int8 netmask; // bits to mask. example: (16 == 255.255.0.0) and (24 == 255.255.255.0)
AP_Networking_IPV4 gwaddr{AP_NETWORKING_DEFAULT_STATIC_GW_ADDR};
2023-07-06 14:46:33 -03:00
AP_Int8 dhcp;
AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR};
2023-07-06 14:46:33 -03:00
AP_Int8 enabled;
2023-07-07 15:15:26 -03:00
AP_Int32 options;
#if AP_NETWORKING_TESTS_ENABLED
AP_Int32 tests;
AP_Networking_IPV4 test_ipaddr{AP_NETWORKING_TEST_IP};
#endif
} param;
2023-07-06 14:46:33 -03:00
AP_Networking_Backend *backend;
HAL_Semaphore sem;
enum class NetworkPortType {
NONE = 0,
UDP_CLIENT = 1,
};
// class for NET_Pn_* parameters
class Port : public AP_SerialManager::RegisteredPort {
public:
/* Do not allow copies */
CLASS_NO_COPY(Port);
Port() {}
static const struct AP_Param::GroupInfo var_info[];
AP_Enum<NetworkPortType> type;
AP_Networking_IPV4 ip {"0.0.0.0"};
AP_Int32 port;
SocketAPM *sock;
bool is_initialized() override {
return true;
}
bool tx_pending() override {
return false;
}
void udp_client_init(void);
void udp_client_loop(void);
private:
bool init_buffers(uint32_t size);
uint32_t txspace() override;
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
size_t _write(const uint8_t *buffer, size_t size) override;
ssize_t _read(uint8_t *buffer, uint16_t count) override;
uint32_t _available() override;
void _end() override {}
void _flush() override {}
bool _discard_input() override;
ByteBuffer *readbuffer;
ByteBuffer *writebuffer;
};
private:
uint32_t announce_ms;
#if AP_NETWORKING_TESTS_ENABLED
enum {
TEST_UDP_CLIENT = (1U<<0),
TEST_TCP_CLIENT = (1U<<1),
};
void start_tests(void);
void test_UDP_client(void);
void test_TCP_client(void);
#endif // AP_NETWORKING_TESTS_ENABLED
// ports for registration with serial manager
Port ports[AP_NETWORKING_NUM_PORTS];
void ports_init(void);
2023-07-06 14:46:33 -03:00
};
2023-07-07 15:15:26 -03:00
namespace AP
{
AP_Networking &network();
2023-07-06 14:46:33 -03:00
};
#endif // AP_NETWORKING_ENABLED