AP_Networking: added networking test suite

This commit is contained in:
Andrew Tridgell 2023-11-13 12:37:10 +11:00 committed by Tom Pittenger
parent bbe7ad484e
commit 4afd0f746b
4 changed files with 140 additions and 0 deletions

View File

@ -56,6 +56,16 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = {
// @Path: AP_Networking_macaddr.cpp // @Path: AP_Networking_macaddr.cpp
AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC), AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC),
#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
AP_GROUPEND AP_GROUPEND
}; };
@ -116,6 +126,10 @@ void AP_Networking::init()
announce_address_changes(); announce_address_changes();
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized"); GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized");
#if AP_NETWORKING_TESTS_ENABLED
start_tests();
#endif
} }
/* /*

View File

@ -165,6 +165,9 @@ private:
AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR}; AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR};
AP_Int8 enabled; AP_Int8 enabled;
AP_Int32 options; AP_Int32 options;
#if AP_NETWORKING_TESTS_ENABLED
AP_Int32 tests;
#endif
} param; } param;
AP_Networking_Backend *backend; AP_Networking_Backend *backend;
@ -173,6 +176,16 @@ private:
private: private:
uint32_t announce_ms; 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
}; };
namespace AP namespace AP

View File

@ -60,3 +60,13 @@
#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR #ifndef AP_NETWORKING_DEFAULT_MAC_ADDR
#define AP_NETWORKING_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46" #define AP_NETWORKING_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46"
#endif #endif
#ifndef AP_NETWORKING_TESTS_ENABLED
#define AP_NETWORKING_TESTS_ENABLED 0
#endif
#if AP_NETWORKING_TESTS_ENABLED
#ifndef AP_NETWORKING_TEST_IP
#define AP_NETWORKING_TEST_IP "192.168.13.15"
#endif
#endif

View File

@ -0,0 +1,103 @@
/*
a set of tests for networking
*/
#include "AP_Networking_Config.h"
#if AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED
#include "AP_Networking.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_HAL/utility/Socket.h>
#include <stdio.h>
extern const AP_HAL::HAL& hal;
/*
start tests
*/
void AP_Networking::start_tests(void)
{
if (param.tests & TEST_UDP_CLIENT) {
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_UDP_client, void),
"UDP_client",
8192, AP_HAL::Scheduler::PRIORITY_IO, -1);
}
if (param.tests & TEST_TCP_CLIENT) {
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_TCP_client, void),
"TCP_client",
8192, AP_HAL::Scheduler::PRIORITY_IO, -1);
}
}
/*
start UDP client test
*/
void AP_Networking::test_UDP_client(void)
{
while (!hal.scheduler->is_system_initialized()) {
hal.scheduler->delay(100);
}
hal.scheduler->delay(1000);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting");
const char *dest = AP_NETWORKING_TEST_IP;
auto *sock = new SocketAPM(true);
if (sock == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket");
return;
}
// connect to the echo service, which is port 7
if (!sock->connect(dest, 7)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: connect failed");
return;
}
while (true) {
hal.scheduler->delay(100);
char *s = nullptr;
asprintf(&s, "hello %u", unsigned(AP_HAL::millis()));
sock->send((const void*)s, strlen(s));
free(s);
uint8_t buf[128] {};
const ssize_t ret = sock->recv(buf, sizeof(buf), 10);
if (ret > 0) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: reply '%s'", (const char *)buf);
}
}
}
/*
start TCP client test
*/
void AP_Networking::test_TCP_client(void)
{
while (!hal.scheduler->is_system_initialized()) {
hal.scheduler->delay(100);
}
hal.scheduler->delay(1000);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting");
const char *dest = AP_NETWORKING_TEST_IP;
auto *sock = new SocketAPM(false);
if (sock == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket");
return;
}
// connect to the echo service, which is port 7
if (!sock->connect(dest, 7)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: connect failed");
return;
}
while (true) {
hal.scheduler->delay(100);
char *s = nullptr;
asprintf(&s, "hello %u", unsigned(AP_HAL::millis()));
sock->send((const void*)s, strlen(s));
free(s);
uint8_t buf[128] {};
const ssize_t ret = sock->recv(buf, sizeof(buf), 10);
if (ret > 0) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: reply '%s'", (const char *)buf);
}
}
}
#endif // AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED