1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

Dterm scaling correction // Code cleanup

This commit is contained in:
borisbstyle 2015-09-19 23:37:41 +02:00
parent f5ad7f6003
commit 0539abc649
13 changed files with 34 additions and 84 deletions

View file

@ -195,8 +195,9 @@ bool fakeAccDetect(acc_t *acc)
}
#endif
bool detectGyro(uint16_t gyroLpf)
bool detectGyro(void)
{
uint16_t gyroLpf = GYRO_LPF;
gyroSensor_e gyroHardware = GYRO_DEFAULT;
gyroAlign = ALIGN_DEFAULT;
@ -633,14 +634,14 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
}
}
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig)
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig)
{
int16_t deg, min;
memset(&acc, 0, sizeof(acc));
memset(&gyro, 0, sizeof(gyro));
if (!detectGyro(gyroLpf)) {
if (!detectGyro()) {
return false;
}
detectAcc(accHardwareToUse);
@ -651,7 +652,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t
if (sensors(SENSOR_ACC))
acc.init();
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
gyroUpdateSampleRate(gyroLpf); // Set gyro refresh rate before initialisation
gyroUpdateSampleRate(); // Set gyro refresh rate before initialisation
gyro.init();
detectMag(magHardwareToUse);