SITL: fixed JSBSim backend for latest version

This commit is contained in:
Willem Eerland 2018-12-17 17:44:07 +11:00 committed by Andrew Tridgell
parent c5a2065a86
commit f8407dd33a
2 changed files with 35 additions and 37 deletions

View File

@ -141,7 +141,7 @@ bool JSBSim::create_templates(void)
fprintf(f, fprintf(f,
"<?xml version=\"1.0\"?>\n" "<?xml version=\"1.0\"?>\n"
"<initialize name=\"Start up location\">\n" "<initialize name=\"Start up location\">\n"
" <latitude unit=\"DEG\"> %f </latitude>\n" " <latitude unit=\"DEG\" type=\"geodetic\"> %f </latitude>\n"
" <longitude unit=\"DEG\"> %f </longitude>\n" " <longitude unit=\"DEG\"> %f </longitude>\n"
" <altitude unit=\"M\"> 1.3 </altitude>\n" " <altitude unit=\"M\"> 1.3 </altitude>\n"
" <vt unit=\"FT/SEC\"> 0.0 </vt>\n" " <vt unit=\"FT/SEC\"> 0.0 </vt>\n"
@ -291,7 +291,7 @@ bool JSBSim::open_control_socket(void)
char startup[] = char startup[] =
"info\n" "info\n"
"resume\n" "resume\n"
"step\n" "iterate 1\n"
"set atmosphere/turb-type 4\n"; "set atmosphere/turb-type 4\n";
sock_control.send(startup, strlen(startup)); sock_control.send(startup, strlen(startup));
return true; return true;
@ -351,7 +351,7 @@ void JSBSim::send_servos(const struct sitl_input &input)
"set atmosphere/wind-mag-fps %f\n" "set atmosphere/wind-mag-fps %f\n"
"set atmosphere/turbulence/milspec/windspeed_at_20ft_AGL-fps %f\n" "set atmosphere/turbulence/milspec/windspeed_at_20ft_AGL-fps %f\n"
"set atmosphere/turbulence/milspec/severity %f\n" "set atmosphere/turbulence/milspec/severity %f\n"
"step\n", "iterate 1\n",
aileron, elevator, rudder, throttle, aileron, elevator, rudder, throttle,
radians(input.wind.direction), radians(input.wind.direction),
wind_speed_fps, wind_speed_fps,

View File

@ -115,12 +115,9 @@ public:
float v_north; // north velocity in local/body frame, fps float v_north; // north velocity in local/body frame, fps
float v_east; // east velocity in local/body frame, fps float v_east; // east velocity in local/body frame, fps
float v_down; // down/vertical velocity in local/body frame, fps float v_down; // down/vertical velocity in local/body frame, fps
float v_wind_body_north; // north velocity in local/body frame float v_body_u; // ECEF velocity in body axis
// relative to local airmass, fps float v_body_v; // ECEF velocity in body axis
float v_wind_body_east; // east velocity in local/body frame float v_body_w; // ECEF velocity in body axis
// relative to local airmass, fps
float v_wind_body_down; // down/vertical velocity in local/body
// frame relative to local airmass, fps
// Accelerations // Accelerations
float A_X_pilot; // X accel in body frame ft/sec^2 float A_X_pilot; // X accel in body frame ft/sec^2
@ -135,7 +132,7 @@ public:
// Engine status // Engine status
uint32_t num_engines; // Number of valid engines uint32_t num_engines; // Number of valid engines
uint32_t eng_state[FG_MAX_ENGINES];// Engine state (off, cranking, running) uint32_t eng_state[FG_MAX_ENGINES]; // Engine state (off, cranking, running)
float rpm[FG_MAX_ENGINES]; // Engine RPM rev/min float rpm[FG_MAX_ENGINES]; // Engine RPM rev/min
float fuel_flow[FG_MAX_ENGINES]; // Fuel flow gallons/hr float fuel_flow[FG_MAX_ENGINES]; // Fuel flow gallons/hr
float fuel_px[FG_MAX_ENGINES]; // Fuel pressure psi float fuel_px[FG_MAX_ENGINES]; // Fuel pressure psi
@ -175,6 +172,7 @@ public:
float speedbrake; float speedbrake;
float spoilers; float spoilers;
// nasty hack .... JSBSim sends in little-endian
void ByteSwap(void); void ByteSwap(void);
}; };