SITL: Fixed rounding lat/lng issue when running JSBSim SITL

Fixed an issue in recieving aircraft state data from JSBSim where
the location was being converted to degrees but as a float. This
caused rounding issues in the lat and lng. Changed the conversion to use
a double.
This commit is contained in:
Shiv Khanna 2022-09-06 12:34:39 -07:00 committed by Andrew Tridgell
parent 765cb4581c
commit 2814605a2c

View File

@ -436,8 +436,8 @@ void JSBSim::recv_fdm(const struct sitl_input &input)
gyro = Vector3f(p, q, r); gyro = Vector3f(p, q, r);
velocity_ef = Vector3f(fdm.v_north, fdm.v_east, fdm.v_down) * FEET_TO_METERS; velocity_ef = Vector3f(fdm.v_north, fdm.v_east, fdm.v_down) * FEET_TO_METERS;
location.lat = degrees(fdm.latitude) * 1.0e7; location.lat = RAD_TO_DEG_DOUBLE * fdm.latitude * 1.0e7;
location.lng = degrees(fdm.longitude) * 1.0e7; location.lng = RAD_TO_DEG_DOUBLE * fdm.longitude * 1.0e7;
location.alt = fdm.agl*100 + home.alt; location.alt = fdm.agl*100 + home.alt;
dcm.from_euler(fdm.phi, fdm.theta, fdm.psi); dcm.from_euler(fdm.phi, fdm.theta, fdm.psi);
airspeed = fdm.vcas * KNOTS_TO_METERS_PER_SECOND; airspeed = fdm.vcas * KNOTS_TO_METERS_PER_SECOND;