From d657fed34afd921ca13905fa67b01338d4c0de2d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Dec 2019 08:49:17 +1100 Subject: [PATCH] SITL: fixed accuracy of lat/lon in AirSim --- libraries/SITL/SIM_AirSim.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/SITL/SIM_AirSim.h b/libraries/SITL/SIM_AirSim.h index eebcfa9c26..9216c14297 100644 --- a/libraries/SITL/SIM_AirSim.h +++ b/libraries/SITL/SIM_AirSim.h @@ -94,7 +94,7 @@ private: Vector3f linear_acceleration; } imu; struct { - float lat, lon, alt; + double lat, lon, alt; } gps; struct { float roll, pitch, yaw; @@ -120,9 +120,9 @@ private: { "", "timestamp", &state.timestamp, DATA_UINT64 }, { "imu", "angular_velocity", &state.imu.angular_velocity, DATA_VECTOR3F }, { "imu", "linear_acceleration", &state.imu.linear_acceleration, DATA_VECTOR3F }, - { "gps", "lat", &state.gps.lat, DATA_FLOAT }, - { "gps", "lon", &state.gps.lon, DATA_FLOAT }, - { "gps", "alt", &state.gps.alt, DATA_FLOAT }, + { "gps", "lat", &state.gps.lat, DATA_DOUBLE }, + { "gps", "lon", &state.gps.lon, DATA_DOUBLE }, + { "gps", "alt", &state.gps.alt, DATA_DOUBLE }, { "pose", "roll", &state.pose.roll, DATA_FLOAT }, { "pose", "pitch", &state.pose.pitch, DATA_FLOAT }, { "pose", "yaw", &state.pose.yaw, DATA_FLOAT },