mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: use SocketAPM_native
This commit is contained in:
parent
931bae5b88
commit
69df468b88
|
@ -18,7 +18,7 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
SocketAPM sock{true};
|
||||
SocketAPM_native sock{true};
|
||||
};
|
||||
|
||||
#endif // HAL_NUM_CAN_IFACES
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <SITL/SIM_JSBSim.h>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_HAL/utility/Socket_native.h>
|
||||
#include <AP_HAL/utility/getopt_cpp.h>
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_HAL/utility/Socket_native.h>
|
||||
|
||||
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;
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <SITL/SIM_JSBSim.h>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_HAL/utility/Socket_native.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <SITL/SIM_JSBSim.h>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_HAL/utility/Socket_native.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -8,6 +8,7 @@
|
|||
#define SITL_MCAST_PORT 20721
|
||||
#define SITL_SERVO_PORT 20722
|
||||
|
||||
#include <AP_HAL/utility/Socket_native.h>
|
||||
#include <SITL/SIM_Gimbal.h>
|
||||
#include <SITL/SIM_ADSB.h>
|
||||
#include <SITL/SIM_ADSB_Sagetech_MXS.h>
|
||||
|
@ -64,7 +65,6 @@
|
|||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <SITL/SITL.h>
|
||||
#include <SITL/SITL_Input.h>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
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;
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
#include <stdint.h>
|
||||
#include <stdarg.h>
|
||||
#include "AP_HAL_SITL_Namespace.h"
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_HAL/utility/Socket_native.h>
|
||||
#include <AP_HAL/utility/RingBuffer.h>
|
||||
#include <AP_CSVReader/AP_CSVReader.h>
|
||||
|
||||
|
|
Loading…
Reference in New Issue