AP_HAL: use SocketAPM_native

This commit is contained in:
Andrew Tridgell 2023-12-26 13:20:40 +11:00
parent cbb3e27519
commit ef67fa4293
2 changed files with 4 additions and 3 deletions

View File

@ -44,7 +44,7 @@
#include <SITL/SIM_RichenPower.h>
#include <SITL/SIM_FETtecOneWireESC.h>
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include <AP_HAL/AP_HAL_Namespace.h>
@ -93,7 +93,7 @@ private:
uint32_t _update_count;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SocketAPM _sitl_rc_in{true};
SocketAPM_native _sitl_rc_in{true};
#endif
SITL::SIM *_sitl;
uint16_t _rcin_port;
@ -220,7 +220,7 @@ private:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// output socket for flightgear viewing
SocketAPM fg_socket{true};
SocketAPM_native fg_socket{true};
#endif
const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;

View File

@ -358,6 +358,7 @@ ssize_t SOCKET_CLASS_NAME::recv(void *buf, size_t size, uint32_t timeout_ms)
*/
void SOCKET_CLASS_NAME::last_recv_address(const char *&ip_addr, uint16_t &port) const
{
// 16 bytes for aaa.bbb.ccc.ddd with null term
static char buf[16];
auto *str = last_recv_address(buf, sizeof(buf), port);
ip_addr = str;