SITL: fixed accuracy of lat/lon in AirSim

This commit is contained in:
Andrew Tridgell 2019-12-17 08:49:17 +11:00
parent e8a3f6d6a1
commit d657fed34a

View File

@ -94,7 +94,7 @@ private:
Vector3f linear_acceleration; Vector3f linear_acceleration;
} imu; } imu;
struct { struct {
float lat, lon, alt; double lat, lon, alt;
} gps; } gps;
struct { struct {
float roll, pitch, yaw; float roll, pitch, yaw;
@ -120,9 +120,9 @@ private:
{ "", "timestamp", &state.timestamp, DATA_UINT64 }, { "", "timestamp", &state.timestamp, DATA_UINT64 },
{ "imu", "angular_velocity", &state.imu.angular_velocity, DATA_VECTOR3F }, { "imu", "angular_velocity", &state.imu.angular_velocity, DATA_VECTOR3F },
{ "imu", "linear_acceleration", &state.imu.linear_acceleration, DATA_VECTOR3F }, { "imu", "linear_acceleration", &state.imu.linear_acceleration, DATA_VECTOR3F },
{ "gps", "lat", &state.gps.lat, DATA_FLOAT }, { "gps", "lat", &state.gps.lat, DATA_DOUBLE },
{ "gps", "lon", &state.gps.lon, DATA_FLOAT }, { "gps", "lon", &state.gps.lon, DATA_DOUBLE },
{ "gps", "alt", &state.gps.alt, DATA_FLOAT }, { "gps", "alt", &state.gps.alt, DATA_DOUBLE },
{ "pose", "roll", &state.pose.roll, DATA_FLOAT }, { "pose", "roll", &state.pose.roll, DATA_FLOAT },
{ "pose", "pitch", &state.pose.pitch, DATA_FLOAT }, { "pose", "pitch", &state.pose.pitch, DATA_FLOAT },
{ "pose", "yaw", &state.pose.yaw, DATA_FLOAT }, { "pose", "yaw", &state.pose.yaw, DATA_FLOAT },