AP_Networking: added NET_TEST_IP for test server IP address
and default to same as default for DDS server
This commit is contained in:
parent
fbe2651840
commit
c54e6ce44b
@ -64,6 +64,10 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = {
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0),
|
||||
|
||||
// @Group: TEST_IP
|
||||
// @Path: AP_Networking_address.cpp
|
||||
AP_SUBGROUPINFO(param.test_ipaddr, "TEST_IP", 8, AP_Networking, AP_Networking_IPV4),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
|
@ -167,6 +167,7 @@ private:
|
||||
AP_Int32 options;
|
||||
#if AP_NETWORKING_TESTS_ENABLED
|
||||
AP_Int32 tests;
|
||||
AP_Networking_IPV4 test_ipaddr{AP_NETWORKING_TEST_IP};
|
||||
#endif
|
||||
} param;
|
||||
|
||||
|
@ -67,6 +67,6 @@
|
||||
|
||||
#if AP_NETWORKING_TESTS_ENABLED
|
||||
#ifndef AP_NETWORKING_TEST_IP
|
||||
#define AP_NETWORKING_TEST_IP "192.168.13.15"
|
||||
#define AP_NETWORKING_TEST_IP "192.168.13.2"
|
||||
#endif
|
||||
#endif
|
||||
|
22
libraries/AP_Networking/AP_Networking_SITL.h
Normal file
22
libraries/AP_Networking/AP_Networking_SITL.h
Normal file
@ -0,0 +1,22 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_Networking_Config.h"
|
||||
|
||||
#if AP_NETWORKING_BACKEND_SITL
|
||||
#include "AP_Networking_Backend.h"
|
||||
|
||||
class AP_Networking_SITL : public AP_Networking_Backend
|
||||
{
|
||||
public:
|
||||
using AP_Networking_Backend::AP_Networking_Backend;
|
||||
|
||||
/* Do not allow copies */
|
||||
CLASS_NO_COPY(AP_Networking_SITL);
|
||||
|
||||
bool init() override {
|
||||
return true;
|
||||
}
|
||||
void update() override {}
|
||||
};
|
||||
|
||||
#endif // AP_NETWORKING_BACKEND_SITL
|
@ -40,7 +40,7 @@ void AP_Networking::test_UDP_client(void)
|
||||
}
|
||||
hal.scheduler->delay(1000);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting");
|
||||
const char *dest = AP_NETWORKING_TEST_IP;
|
||||
const char *dest = param.test_ipaddr.get_str();
|
||||
auto *sock = new SocketAPM(true);
|
||||
if (sock == nullptr) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket");
|
||||
@ -75,7 +75,7 @@ void AP_Networking::test_TCP_client(void)
|
||||
}
|
||||
hal.scheduler->delay(1000);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting");
|
||||
const char *dest = AP_NETWORKING_TEST_IP;
|
||||
const char *dest = param.test_ipaddr.get_str();
|
||||
auto *sock = new SocketAPM(false);
|
||||
if (sock == nullptr) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket");
|
||||
|
Loading…
Reference in New Issue
Block a user