diff --git a/libraries/SITL/SIM_ADSB.h b/libraries/SITL/SIM_ADSB.h index 9b9682c15b..c80cf2668e 100644 --- a/libraries/SITL/SIM_ADSB.h +++ b/libraries/SITL/SIM_ADSB.h @@ -22,7 +22,7 @@ #if HAL_SIM_ADSB_ENABLED -#include +#include #include "SIM_Aircraft.h" diff --git a/libraries/SITL/SIM_AirSim.h b/libraries/SITL/SIM_AirSim.h index 7e3b447817..1e9b75c0e6 100644 --- a/libraries/SITL/SIM_AirSim.h +++ b/libraries/SITL/SIM_AirSim.h @@ -26,7 +26,7 @@ #if HAL_SIM_AIRSIM_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index eb6d01c3b4..b3a5699f99 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -26,7 +26,7 @@ #if HAL_SIM_CRRCSIM_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -81,7 +81,7 @@ private: bool heli_servos; double last_timestamp; - SocketAPM sock; + SocketAPM_native sock; }; } // namespace SITL diff --git a/libraries/SITL/SIM_EFI_Hirth.h b/libraries/SITL/SIM_EFI_Hirth.h index 8ccbb8286a..0aec264f76 100644 --- a/libraries/SITL/SIM_EFI_Hirth.h +++ b/libraries/SITL/SIM_EFI_Hirth.h @@ -29,7 +29,7 @@ status EFI_STATUS #pragma once #include -#include +#include #include "SIM_SerialDevice.h" namespace SITL { diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index 352fbd4458..7c0151a165 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -28,8 +28,8 @@ status EFI_STATUS #pragma once +#include #include -#include #include "SIM_SerialDevice.h" namespace SITL { diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index afd89d2be1..36d63e0d67 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -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; diff --git a/libraries/SITL/SIM_FlightAxis.h b/libraries/SITL/SIM_FlightAxis.h index 592cc741a5..0567997e1f 100644 --- a/libraries/SITL/SIM_FlightAxis.h +++ b/libraries/SITL/SIM_FlightAxis.h @@ -26,7 +26,7 @@ #if HAL_SIM_FLIGHTAXIS_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index 4da05353ba..6a13d8b8e5 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -27,7 +27,7 @@ #if HAL_SIM_GAZEBO_ENABLED #include "SIM_Aircraft.h" -#include +#include 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; diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index 53a2212a29..2cedd3a1cf 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -26,7 +26,7 @@ #if HAL_SIM_GIMBAL_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_JSBSim.h b/libraries/SITL/SIM_JSBSim.h index fda323e943..bbb2c1a46a 100644 --- a/libraries/SITL/SIM_JSBSim.h +++ b/libraries/SITL/SIM_JSBSim.h @@ -26,7 +26,7 @@ #if HAL_SIM_JSBSIM_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_JSON.h b/libraries/SITL/SIM_JSON.h index 22582f0ae4..b168219d9d 100644 --- a/libraries/SITL/SIM_JSON.h +++ b/libraries/SITL/SIM_JSON.h @@ -22,7 +22,7 @@ #if HAL_SIM_JSON_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_JSON_Master.h b/libraries/SITL/SIM_JSON_Master.h index 9a568f6ed1..f4bcc13994 100644 --- a/libraries/SITL/SIM_JSON_Master.h +++ b/libraries/SITL/SIM_JSON_Master.h @@ -27,7 +27,7 @@ #if HAL_SIM_JSON_MASTER_ENABLED #include "SITL_Input.h" -#include +#include #include 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; diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index 221c6c1abe..c4c6249869 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -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"); } diff --git a/libraries/SITL/SIM_Morse.h b/libraries/SITL/SIM_Morse.h index 5e45ab9f93..9445c26d58 100644 --- a/libraries/SITL/SIM_Morse.h +++ b/libraries/SITL/SIM_Morse.h @@ -26,7 +26,7 @@ #if HAL_SIM_MORSE_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_Scrimmage.h b/libraries/SITL/SIM_Scrimmage.h index e6228cb281..2fa8dfcbaf 100644 --- a/libraries/SITL/SIM_Scrimmage.h +++ b/libraries/SITL/SIM_Scrimmage.h @@ -28,7 +28,7 @@ #include -#include +#include #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 diff --git a/libraries/SITL/SIM_Ship.h b/libraries/SITL/SIM_Ship.h index cbb91ccba4..afdff43b37 100644 --- a/libraries/SITL/SIM_Ship.h +++ b/libraries/SITL/SIM_Ship.h @@ -22,7 +22,7 @@ #if AP_SIM_SHIP_ENABLED -#include +#include #include #include #include @@ -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; diff --git a/libraries/SITL/SIM_SilentWings.h b/libraries/SITL/SIM_SilentWings.h index 50739387a3..75fdd3984f 100644 --- a/libraries/SITL/SIM_SilentWings.h +++ b/libraries/SITL/SIM_SilentWings.h @@ -23,7 +23,7 @@ #if HAL_SIM_SILENTWINGS_ENABLED -#include +#include #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; diff --git a/libraries/SITL/SIM_Webots.cpp b/libraries/SITL/SIM_Webots.cpp index ac6c4655e9..134fdc6236 100644 --- a/libraries/SITL/SIM_Webots.cpp +++ b/libraries/SITL/SIM_Webots.cpp @@ -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"); } diff --git a/libraries/SITL/SIM_Webots.h b/libraries/SITL/SIM_Webots.h index ef6ea1454a..5457d6cd96 100644 --- a/libraries/SITL/SIM_Webots.h +++ b/libraries/SITL/SIM_Webots.h @@ -27,7 +27,7 @@ #if HAL_SIM_WEBOTS_ENABLED #include -#include +#include #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; diff --git a/libraries/SITL/SIM_Webots_Python.h b/libraries/SITL/SIM_Webots_Python.h index 194d8cd648..ec3e8ba4b5 100644 --- a/libraries/SITL/SIM_Webots_Python.h +++ b/libraries/SITL/SIM_Webots_Python.h @@ -27,7 +27,7 @@ #if HAL_SIM_WEBOTSPYTHON_ENABLED #include "SIM_Aircraft.h" -#include +#include 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; diff --git a/libraries/SITL/SIM_XPlane.h b/libraries/SITL/SIM_XPlane.h index 8405143932..8c90ea6c21 100644 --- a/libraries/SITL/SIM_XPlane.h +++ b/libraries/SITL/SIM_XPlane.h @@ -26,7 +26,7 @@ #if HAL_SIM_XPLANE_ENABLED -#include +#include #include #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; diff --git a/libraries/SITL/SIM_last_letter.h b/libraries/SITL/SIM_last_letter.h index ae7cae5ecf..d8afa83ba0 100644 --- a/libraries/SITL/SIM_last_letter.h +++ b/libraries/SITL/SIM_last_letter.h @@ -26,7 +26,7 @@ #if HAL_SIM_LAST_LETTER_ENABLED -#include +#include #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