SITL: setup turbulence in JSBSim

This commit is contained in:
Andrew Tridgell 2015-06-29 11:25:59 +10:00
parent 92c9779d18
commit ff88932091
3 changed files with 13 additions and 4 deletions

View File

@ -41,7 +41,7 @@ public:
struct {
float speed; // m/s
float direction; // degrees 0..360
float turbulance;
float turbulence;
} wind;
};

View File

@ -281,7 +281,11 @@ bool JSBSim::open_control_socket(void)
sock_control.set_blocking(false);
opened_control_socket = true;
char startup[] = "info\nresume\nstep\n";
char startup[] =
"info\n"
"resume\n"
"step\n"
"set atmosphere/turb-type 4\n";
sock_control.send(startup, strlen(startup));
return true;
}
@ -330,6 +334,7 @@ void JSBSim::send_servos(const struct sitl_input &input)
elevator = (ch2-ch1)/2.0f;
rudder = (ch2+ch1)/2.0f;
}
float wind_speed_fps = input.wind.speed / FEET_TO_METERS;
asprintf(&buf,
"set fcs/aileron-cmd-norm %f\n"
"set fcs/elevator-cmd-norm %f\n"
@ -337,10 +342,14 @@ void JSBSim::send_servos(const struct sitl_input &input)
"set fcs/throttle-cmd-norm %f\n"
"set atmosphere/psiw-rad %f\n"
"set atmosphere/wind-mag-fps %f\n"
"set atmosphere/turbulence/milspec/windspeed_at_20ft_AGL-fps %f\n"
"set atmosphere/turbulence/milspec/severity %f\n"
"step\n",
aileron, elevator, rudder, throttle,
radians(input.wind.direction),
input.wind.speed / FEET_TO_METERS);
wind_speed_fps,
wind_speed_fps/3,
input.wind.turbulence);
ssize_t buflen = strlen(buf);
ssize_t sent = sock_control.send(buf, buflen);
free(buf);

View File

@ -38,7 +38,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0.2f),
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0),
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),