mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_SITL: send state to flightgear viewer
This commit is contained in:
parent
55e8e0742a
commit
83c8505b3c
@ -18,6 +18,7 @@
|
||||
#include <sys/select.h>
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <SITL/SIM_JSBSim.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -96,6 +97,8 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||
if (enable_ADSB) {
|
||||
adsb = new ADSB(_sitl->state, home_str);
|
||||
}
|
||||
|
||||
fg_socket.connect("127.0.0.1", 5503);
|
||||
}
|
||||
|
||||
if (_synthetic_clock_mode) {
|
||||
@ -231,6 +234,27 @@ void SITL_State::_fdm_input(void)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
output current state to flightgear
|
||||
*/
|
||||
void SITL_State::_output_to_flightgear(void)
|
||||
{
|
||||
SITL::FGNetFDM fdm {};
|
||||
const SITL::sitl_fdm &sfdm = _sitl->state;
|
||||
|
||||
fdm.version = 0x18;
|
||||
fdm.padding = 0;
|
||||
fdm.longitude = radians(sfdm.longitude);
|
||||
fdm.latitude = radians(sfdm.latitude);
|
||||
fdm.altitude = sfdm.altitude;
|
||||
fdm.agl = sfdm.altitude;
|
||||
fdm.phi = radians(sfdm.rollDeg);
|
||||
fdm.theta = radians(sfdm.pitchDeg);
|
||||
fdm.psi = radians(sfdm.yawDeg);
|
||||
fdm.ByteSwap();
|
||||
|
||||
fg_socket.send(&fdm, sizeof(fdm));
|
||||
}
|
||||
|
||||
/*
|
||||
get FDM input from a local model
|
||||
@ -259,6 +283,8 @@ void SITL_State::_fdm_input_local(void)
|
||||
adsb->update();
|
||||
}
|
||||
|
||||
_output_to_flightgear();
|
||||
|
||||
// update simulation time
|
||||
hal.scheduler->stop_clock(_sitl->state.timestamp_us);
|
||||
|
||||
|
@ -24,6 +24,7 @@
|
||||
#include <SITL/SITL.h>
|
||||
#include <SITL/SIM_Gimbal.h>
|
||||
#include <SITL/SIM_ADSB.h>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
class HAL_SITL;
|
||||
|
||||
@ -119,6 +120,7 @@ private:
|
||||
float airspeed, float altitude);
|
||||
void _fdm_input(void);
|
||||
void _fdm_input_local(void);
|
||||
void _output_to_flightgear(void);
|
||||
void _simulator_servos(SITL::Aircraft::sitl_input &input);
|
||||
void _simulator_output(bool synthetic_clock_mode);
|
||||
void _apply_servo_filter(float deltat);
|
||||
@ -205,6 +207,9 @@ private:
|
||||
bool enable_ADSB;
|
||||
SITL::ADSB *adsb;
|
||||
|
||||
// output socket for flightgear viewing
|
||||
SocketAPM fg_socket{true};
|
||||
|
||||
// TCP address to connect uartC to
|
||||
const char *_client_address;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user