mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Avoid passing a uint8_t to a gyro method that is only used during gyro
calibration. Conflicts: src/config.c src/flight_imu.c src/mw.h src/sensors.c src/serial_cli.c
This commit is contained in:
parent
9d56b4a00f
commit
11863e5c34
7 changed files with 29 additions and 10 deletions
|
@ -16,9 +16,17 @@
|
|||
|
||||
uint16_t calibratingG = 0;
|
||||
uint16_t acc_1G = 256; // this is the 1G measured acceleration.
|
||||
|
||||
static gyroConfig_t *gyroConfig;
|
||||
|
||||
gyro_t gyro; // gyro access functions
|
||||
sensor_align_e gyroAlign = 0;
|
||||
|
||||
void useGyroConfig(gyroConfig_t *gyroConfigToUse)
|
||||
{
|
||||
gyroConfig = gyroConfigToUse;
|
||||
}
|
||||
|
||||
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired)
|
||||
{
|
||||
calibratingG = calibrationCyclesRequired;
|
||||
|
@ -83,14 +91,14 @@ static void applyGyroZero(void)
|
|||
}
|
||||
}
|
||||
|
||||
void gyroGetADC(uint8_t gyroMovementCalibrationThreshold)
|
||||
void gyroGetADC(void)
|
||||
{
|
||||
// range: +/- 8192; +/- 2000 deg/sec
|
||||
gyro.read(gyroADC);
|
||||
alignSensors(gyroADC, gyroADC, gyroAlign);
|
||||
|
||||
if (!isGyroCalibrationComplete()) {
|
||||
performAcclerationCalibration(gyroMovementCalibrationThreshold);
|
||||
performAcclerationCalibration(gyroConfig->gyroMovementCalibrationThreshold);
|
||||
}
|
||||
|
||||
applyGyroZero();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue