mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: fixed orientation of XPlane11 gyro data
This commit is contained in:
parent
13fbca7455
commit
5a4fee6ac3
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user