mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
CC3D - Change the default alignment of the board to match the default
open pilot alignment. This makes it easier for new users to adopt cleanflight without having to look up the alignment cli settings or rotate their boards in their existing aircraft. See discussion here: http://forums.openpilot.org/topic/43569-baseflightcleanflight-ported-to-cc3d/?p=360886
This commit is contained in:
parent
6ff9483425
commit
95852d0bdf
1 changed files with 6 additions and 0 deletions
|
@ -229,6 +229,9 @@ bool detectGyro(uint16_t gyroLpf)
|
|||
|
||||
#ifdef USE_GYRO_SPI_MPU6000
|
||||
if (mpu6000SpiGyroDetect(&gyro, gyroLpf)) {
|
||||
#ifdef CC3D
|
||||
gyroAlign = CW270_DEG;
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
@ -320,6 +323,9 @@ retry:
|
|||
case ACC_SPI_MPU6000:
|
||||
if (mpu6000SpiAccDetect(&acc)) {
|
||||
accHardware = ACC_SPI_MPU6000;
|
||||
#ifdef CC3D
|
||||
accAlign = CW270_DEG;
|
||||
#endif
|
||||
if (accHardwareToUse == ACC_SPI_MPU6000)
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue