mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
OP-378: Map gyros to board orientation
This commit is contained in:
parent
4a9e7604a1
commit
52e72f20e2
@ -609,9 +609,9 @@ bool get_accel_gyro_data()
|
||||
accel_data.filtered.x = accel[0] * 0.0025;
|
||||
accel_data.filtered.y = accel[1] * 0.0025;
|
||||
accel_data.filtered.z = accel[2] * 0.0025;
|
||||
gyro_data.filtered.x = gyro[0] * 0.00763 * DEG_TO_RAD;;
|
||||
gyro_data.filtered.y = gyro[1] * 0.00763 * DEG_TO_RAD;;
|
||||
gyro_data.filtered.z = gyro[2] * 0.00763 * DEG_TO_RAD;;
|
||||
gyro_data.filtered.x = -gyro[1] * 0.00763 * DEG_TO_RAD;;
|
||||
gyro_data.filtered.y = -gyro[0] * 0.00763 * DEG_TO_RAD;;
|
||||
gyro_data.filtered.z = -gyro[2] * 0.00763 * DEG_TO_RAD;;
|
||||
|
||||
|
||||
AttitudeRawData raw;
|
||||
|
Loading…
x
Reference in New Issue
Block a user