mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 23:48:31 -04:00
SITL: fixed mag field in JSBSim and last_letter
This commit is contained in:
parent
ba2382c409
commit
5b7b799046
libraries/SITL
@ -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];
|
||||
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user