mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed wind support in JSBSim
This commit is contained in:
parent
9ac892acea
commit
091a1e7fe0
|
@ -38,6 +38,11 @@ public:
|
|||
*/
|
||||
struct sitl_input {
|
||||
uint16_t servos[16];
|
||||
struct {
|
||||
float speed; // m/s
|
||||
float direction; // degrees 0..360
|
||||
float turbulance;
|
||||
} wind;
|
||||
};
|
||||
|
||||
/*
|
||||
|
|
|
@ -34,6 +34,7 @@ extern const AP_HAL::HAL& hal;
|
|||
#pragma GCC diagnostic ignored "-Wunused-result"
|
||||
|
||||
#define DEBUG_JSBSIM 1
|
||||
#define FEET_TO_METERS 0.3048f
|
||||
|
||||
/*
|
||||
constructor
|
||||
|
@ -336,8 +337,12 @@ void JSBSim::send_servos(const struct sitl_input &input)
|
|||
"set fcs/elevator-cmd-norm %f\n"
|
||||
"set fcs/rudder-cmd-norm %f\n"
|
||||
"set fcs/throttle-cmd-norm %f\n"
|
||||
"set atmosphere/psiw-rad %f\n"
|
||||
"set atmosphere/wind-mag-fps %f\n"
|
||||
"step\n",
|
||||
aileron, elevator, rudder, throttle);
|
||||
aileron, elevator, rudder, throttle,
|
||||
radians(input.wind.direction),
|
||||
input.wind.speed / FEET_TO_METERS);
|
||||
ssize_t buflen = strlen(buf);
|
||||
ssize_t sent = sock_control.send(buf, buflen);
|
||||
free(buf);
|
||||
|
@ -353,8 +358,6 @@ void JSBSim::send_servos(const struct sitl_input &input)
|
|||
}
|
||||
}
|
||||
|
||||
#define FEET_TO_METERS 0.3048f
|
||||
|
||||
/* nasty hack ....
|
||||
JSBSim sends in little-endian
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue