diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.h b/libraries/AP_HAL_SITL/CAN_Multicast.h index 07b39982a7..4bff83d4c7 100644 --- a/libraries/AP_HAL_SITL/CAN_Multicast.h +++ b/libraries/AP_HAL_SITL/CAN_Multicast.h @@ -18,7 +18,7 @@ public: } private: - SocketAPM sock{true}; + SocketAPM_native sock{true}; }; #endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 618f26a1ae..a65e56310e 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index 47bb61ee79..61453d4a0f 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -22,7 +22,7 @@ #include #include #include -#include +#include class SimMCast : public SITL::Aircraft { public: @@ -30,8 +30,8 @@ public: void update(const struct sitl_input &input) override; private: - SocketAPM sock{true}; - SocketAPM servo_sock{true}; + SocketAPM_native sock{true}; + SocketAPM_native servo_sock{true}; // offset between multicast timestamp and local timestamp uint64_t base_time_us; diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 4b08727d8e..e2e27e1fa0 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -23,7 +23,7 @@ #include #include -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 5e5ce885b1..4aa73d4a11 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -85,7 +85,7 @@ private: Scheduler *_scheduler; - SocketAPM _sitl_rc_in{true}; + SocketAPM_native _sitl_rc_in{true}; bool _rc_in_started; uint16_t _rcin_port; uint16_t _fg_view_port; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index f05bbf20b1..ae2603e6dd 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 509391760c..4b59268ef8 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -8,6 +8,7 @@ #define SITL_MCAST_PORT 20721 #define SITL_SERVO_PORT 20722 +#include #include #include #include @@ -64,7 +65,6 @@ #include #include #include -#include class HAL_SITL; @@ -220,7 +220,7 @@ public: SITL::EFI_Hirth *efi_hirth; // output socket for flightgear viewing - SocketAPM fg_socket{true}; + SocketAPM_native fg_socket{true}; const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index bf875b7abf..70d1fa332f 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -6,7 +6,7 @@ #include #include #include "AP_HAL_SITL_Namespace.h" -#include +#include #include #include