SITL: use SocketAPM_native

This commit is contained in:
Andrew Tridgell 2023-12-26 13:21:11 +11:00
parent 213cdcef4b
commit adffd93894
22 changed files with 46 additions and 46 deletions

View File

@ -22,7 +22,7 @@
#if HAL_SIM_ADSB_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"

View File

@ -26,7 +26,7 @@
#if HAL_SIM_AIRSIM_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
namespace SITL {
@ -78,7 +78,7 @@ private:
// connection_info_.sitl_ip_port
uint16_t airsim_control_port = 9002;
SocketAPM sock;
SocketAPM_native sock;
double average_frame_time;
uint64_t frame_counter;

View File

@ -26,7 +26,7 @@
#if HAL_SIM_CRRCSIM_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -81,7 +81,7 @@ private:
bool heli_servos;
double last_timestamp;
SocketAPM sock;
SocketAPM_native sock;
};
} // namespace SITL

View File

@ -29,7 +29,7 @@ status EFI_STATUS
#pragma once
#include <SITL/SITL.h>
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_SerialDevice.h"
namespace SITL {

View File

@ -28,8 +28,8 @@ status EFI_STATUS
#pragma once
#include <AP_HAL/utility/Socket_native.h>
#include <SITL/SITL.h>
#include <AP_HAL/utility/Socket.h>
#include "SIM_SerialDevice.h"
namespace SITL {

View File

@ -590,7 +590,7 @@ void FlightAxis::socket_creator(void)
pthread_cond_wait(&sockcond2, &sockmtx);
}
pthread_mutex_unlock(&sockmtx);
auto *sck = new SocketAPM(false);
auto *sck = new SocketAPM_native(false);
if (sck == nullptr) {
usleep(500);
continue;

View File

@ -26,7 +26,7 @@
#if HAL_SIM_FLIGHTAXIS_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -193,8 +193,8 @@ private:
const char *controller_ip = "127.0.0.1";
uint16_t controller_port = 18083;
SocketAPM *socknext;
SocketAPM *sock;
SocketAPM_native *socknext;
SocketAPM_native *sock;
char replybuf[10000];
pid_t socket_pid;
uint32_t sock_error_count;

View File

@ -27,7 +27,7 @@
#if HAL_SIM_GAZEBO_ENABLED
#include "SIM_Aircraft.h"
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
namespace SITL {
@ -76,7 +76,7 @@ private:
double last_timestamp;
SocketAPM socket_sitl;
SocketAPM_native socket_sitl;
const char *_gazebo_address = "127.0.0.1";
int _gazebo_port = 9002;
static const uint64_t GAZEBO_TIMEOUT_US = 5000000;

View File

@ -26,7 +26,7 @@
#if HAL_SIM_GIMBAL_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -101,7 +101,7 @@ private:
uint8_t vehicle_system_id;
uint8_t vehicle_component_id;
SocketAPM mav_socket;
SocketAPM_native mav_socket;
struct {
// socket to telem2 on aircraft
bool connected;

View File

@ -26,7 +26,7 @@
#if HAL_SIM_JSBSIM_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -49,10 +49,10 @@ public:
private:
// tcp input control socket to JSBSIm
SocketAPM sock_control;
SocketAPM_native sock_control;
// UDP packets from JSBSim in fgFDM format
SocketAPM sock_fgfdm;
SocketAPM_native sock_fgfdm;
bool initialised;

View File

@ -22,7 +22,7 @@
#if HAL_SIM_JSON_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
namespace SITL {
@ -64,7 +64,7 @@ private:
// default connection_info_.sitl_ip_port
uint16_t control_port = 9002;
SocketAPM sock;
SocketAPM_native sock;
uint32_t frame_counter;
double last_timestamp_s;

View File

@ -27,7 +27,7 @@
#if HAL_SIM_JSON_MASTER_ENABLED
#include "SITL_Input.h"
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include <AP_Math/AP_Math.h>
namespace SITL {
@ -48,8 +48,8 @@ public:
private:
struct socket_list {
SocketAPM sock_in{true};
SocketAPM sock_out{true};
SocketAPM_native sock_in{true};
SocketAPM_native sock_out{true};
uint8_t instance;
bool connected;
socket_list *next;

View File

@ -261,7 +261,7 @@ bool Morse::parse_sensors(const char *json)
bool Morse::connect_sockets(void)
{
if (!sensors_sock) {
sensors_sock = new SocketAPM(false);
sensors_sock = new SocketAPM_native(false);
if (!sensors_sock) {
AP_HAL::panic("Out of memory for sensors socket");
}
@ -280,7 +280,7 @@ bool Morse::connect_sockets(void)
printf("Sensors connected\n");
}
if (!control_sock) {
control_sock = new SocketAPM(false);
control_sock = new SocketAPM_native(false);
if (!control_sock) {
AP_HAL::panic("Out of memory for control socket");
}

View File

@ -26,7 +26,7 @@
#if HAL_SIM_MORSE_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
namespace SITL {
@ -51,7 +51,7 @@ private:
// loopback to convert inbound Morse lidar data into inbound mavlink msgs
const char *mavlink_loopback_address = "127.0.0.1";
const uint16_t mavlink_loopback_port = 5762;
SocketAPM mav_socket { false };
SocketAPM_native mav_socket { false };
struct {
// socket to telem2 on aircraft
bool connected;
@ -91,8 +91,8 @@ private:
uint8_t sensor_buffer[50000];
uint32_t sensor_buffer_len;
SocketAPM *sensors_sock;
SocketAPM *control_sock;
SocketAPM_native *sensors_sock;
SocketAPM_native *control_sock;
uint32_t no_data_counter;
uint32_t connect_counter;

View File

@ -28,7 +28,7 @@
#include <string>
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -84,8 +84,8 @@ private:
void send_servos(const struct sitl_input &input);
uint64_t prev_timestamp_us;
SocketAPM recv_sock;
SocketAPM send_sock;
SocketAPM_native recv_sock;
SocketAPM_native send_sock;
};
} // namespace SITL

View File

@ -22,7 +22,7 @@
#if AP_SIM_SHIP_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include <AP_Math/AP_Math.h>
#include <AP_Common/Location.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
@ -83,7 +83,7 @@ private:
uint32_t last_report_ms;
uint32_t last_heartbeat_ms;
SocketAPM mav_socket { false };
SocketAPM_native mav_socket { false };
bool mavlink_connected;
mavlink_status_t mav_status;

View File

@ -23,7 +23,7 @@
#if HAL_SIM_SILENTWINGS_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -109,7 +109,7 @@ private:
/* ArduPlane's internal time when the first packet from Silent Wings is received. */
uint64_t time_base_us;
SocketAPM sock;
SocketAPM_native sock;
const char *_sw_address = "127.0.0.1";
int _port_in = 6060;
int _sw_port = 6070;

View File

@ -291,7 +291,7 @@ bool Webots::parse_sensors(const char *json)
bool Webots::connect_sockets(void)
{
if (!sim_sock) {
sim_sock = new SocketAPM(false);
sim_sock = new SocketAPM_native(false);
if (!sim_sock) {
AP_HAL::panic("Out of memory for sensors socket");
}

View File

@ -27,7 +27,7 @@
#if HAL_SIM_WEBOTS_ENABLED
#include <cmath>
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
namespace SITL {
@ -79,7 +79,7 @@ private:
uint8_t sensor_buffer[50000];
uint32_t sensor_buffer_len;
SocketAPM *sim_sock;
SocketAPM_native *sim_sock;
uint32_t connect_counter;

View File

@ -27,7 +27,7 @@
#if HAL_SIM_WEBOTSPYTHON_ENABLED
#include "SIM_Aircraft.h"
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
namespace SITL {
@ -78,7 +78,7 @@ private:
double last_timestamp;
SocketAPM socket_sitl;
SocketAPM_native socket_sitl;
const char* _webots_address = "127.0.0.1";
int _webots_port = 9002;
static const uint64_t WEBOTS_TIMEOUT_US = 5000000;

View File

@ -26,7 +26,7 @@
#if HAL_SIM_XPLANE_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include <AP_Filesystem/AP_Filesystem.h>
#include "SIM_Aircraft.h"
@ -70,8 +70,8 @@ private:
uint16_t xplane_port = 49000;
uint16_t bind_port = 49001;
// udp socket, input and output
SocketAPM socket_in{true};
SocketAPM socket_out{true};
SocketAPM_native socket_in{true};
SocketAPM_native socket_out{true};
uint64_t time_base_us;
uint32_t last_data_time_ms;

View File

@ -26,7 +26,7 @@
#if HAL_SIM_LAST_LETTER_ENABLED
#include <AP_HAL/utility/Socket.h>
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
@ -77,7 +77,7 @@ private:
void start_last_letter(void);
uint64_t last_timestamp_us;
SocketAPM sock;
SocketAPM_native sock;
};
} // namespace SITL