From 5b7b799046b73cd232c4a4d28330c3b9943216ae Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 20 Jun 2016 11:07:34 +1000 Subject: [PATCH] SITL: fixed mag field in JSBSim and last_letter --- libraries/SITL/SIM_JSBSim.cpp | 3 +++ libraries/SITL/SIM_last_letter.cpp | 3 +++ 2 files changed, 6 insertions(+) diff --git a/libraries/SITL/SIM_JSBSim.cpp b/libraries/SITL/SIM_JSBSim.cpp index 22010c333e..ad4cdfe68f 100644 --- a/libraries/SITL/SIM_JSBSim.cpp +++ b/libraries/SITL/SIM_JSBSim.cpp @@ -423,6 +423,9 @@ void JSBSim::recv_fdm(const struct sitl_input &input) airspeed = fdm.vcas * FEET_TO_METERS; airspeed_pitot = airspeed; + // update magnetic field + update_mag_field_bf(); + rpm1 = fdm.rpm[0]; rpm2 = fdm.rpm[1]; diff --git a/libraries/SITL/SIM_last_letter.cpp b/libraries/SITL/SIM_last_letter.cpp index 965bb7ec3d..ffb198f1f8 100644 --- a/libraries/SITL/SIM_last_letter.cpp +++ b/libraries/SITL/SIM_last_letter.cpp @@ -125,6 +125,9 @@ void last_letter::recv_fdm(const struct sitl_input &input) airspeed = pkt.airspeed; airspeed_pitot = pkt.airspeed; + // update magnetic field + update_mag_field_bf(); + // auto-adjust to last_letter frame rate uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us; time_now_us += deltat_us;