1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Loop synced to Gyro

Remove double MPU_RA_PWR_MGMT_1

Looptime to Gyro refresh rate

disable 2khz when acc used for F3

Gyro sync code improvement

doc change
This commit is contained in:
borisbstyle 2015-08-05 00:16:52 +02:00
parent 07b9aceb7c
commit 26deeb8ff6
16 changed files with 162 additions and 30 deletions

View file

@ -39,6 +39,7 @@
#include "drivers/bus_spi.h"
#include "drivers/accgyro_spi_mpu6000.h"
#include "drivers/accgyro_spi_mpu6500.h"
#include "drivers/gyro_sync.h"
#include "drivers/barometer.h"
#include "drivers/barometer_bmp085.h"
@ -596,7 +597,7 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
}
}
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig)
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, int16_t magDeclinationFromConfig, uint32_t looptime)
{
int16_t deg, min;
@ -614,6 +615,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(looptime, gyroLpf); // Set gyro refresh rate before initialisation
gyro.init();
detectMag(magHardwareToUse);