diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 251e3942d6..60db27ea92 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -252,8 +252,8 @@ void SITL_State::_output_to_flightgear(void) fdm.version = 0x18; fdm.padding = 0; - fdm.longitude = radians(sfdm.longitude); - fdm.latitude = radians(sfdm.latitude); + fdm.longitude = DEG_TO_RAD_DOUBLE*sfdm.longitude; + fdm.latitude = DEG_TO_RAD_DOUBLE*sfdm.latitude; fdm.altitude = sfdm.altitude; fdm.agl = sfdm.altitude; fdm.phi = radians(sfdm.rollDeg);