Browse Source

AP_HAL_SITL: Use double point precision when converting langitudes and longitudes from degrees to radians.

See #9536
master
Kristian Klausen 6 years ago committed by Andrew Tridgell
parent
commit
d7f529d3c6
  1. 4
      libraries/AP_HAL_SITL/SITL_State.cpp

4
libraries/AP_HAL_SITL/SITL_State.cpp

@ -252,8 +252,8 @@ void SITL_State::_output_to_flightgear(void) @@ -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);

Loading…
Cancel
Save