mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_SITL: Use double point precision when converting langitudes and longitudes from degrees to radians.
See #9536
This commit is contained in:
parent
e9c1abfc3c
commit
d7f529d3c6
@ -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…
Reference in New Issue
Block a user