SITL: fixed orientation of XPlane11 gyro data

This commit is contained in:
Andrew Tridgell 2023-02-19 11:16:02 +11:00
parent 13fbca7455
commit 5a4fee6ac3

View File

@ -457,8 +457,9 @@ bool XPlane::receive_data(void)
gyro.y = radians(data[2]);
gyro.z = radians(data[3]);
} else {
gyro.x = data[1];
gyro.y = data[2];
// xplane 11
gyro.x = data[2];
gyro.y = data[1];
gyro.z = data[3];
}
// we only count gyro data towards data counts