1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 01:35:35 +03:00

Gyro Sync feature (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

MPU6500 INT_STATUS support // MPU3500 dummy handling

Enable full 1khz sampling on F1 boards (no acc mode)

Add MPU3050 INT_STATUS

F1 target decreased max refresh

Configurable optione (sync_gyro_to_loop)

correction watchdog

correct filter

Coding style and cleanup code

Cli.md

Bump EEPROM version

MPU6050 MPU DATA READY Pin instead of i2c

Add more targets and corrections

correction to CC3D

ident

MPU6500 correction

INT_ENABLE MPU6500

add interrupt mpu6500

MPU6500 corrections from rebase

MPU6500 correct

Final fix to compile // ready for testing and review

MPU6000 / MPU3050 Corrections

Add CC3D extiConfig

add mpu6500

Fix intStatus position

fix returns

Add COLIBRI_RACE MPU INT

Change CLI name to gyro_sync

This is shorter typing and speaks for itself

Fix MotoLab After rebase

Add motolab

Full gyro Sync rework

Idents etc

Doc update

more corrections

Fix serial_cli

refactor // ident

GPL

single line

runloop refactor
This commit is contained in:
borisbstyle 2015-08-05 00:16:52 +02:00
parent 6926c2057f
commit 10a96b0dfc
25 changed files with 238 additions and 75 deletions

View file

@ -45,6 +45,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"
@ -150,6 +151,19 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
return &MotolabF3MPUIntExtiConfig;
#endif
#if defined(COLIBRI_RACE)
static const extiConfig_t colibriRaceMPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_5,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource5,
.exti_line = EXTI_Line5,
.exti_irqn = EXTI9_5_IRQn
};
return &colibriRaceMPUIntExtiConfig;
#endif
return NULL;
}
@ -630,8 +644,10 @@ 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 gyroLpf, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse,
int16_t magDeclinationFromConfig,
uint32_t looptime, uint8_t gyroSync, uint8_t gyroSyncDenominator) {
int16_t deg, min;
memset(&acc, 0, sizeof(acc));
@ -656,6 +672,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, gyroSync, gyroSyncDenominator); // Set gyro sampling rate divider before initialization
gyro.init(gyroLpf);
detectMag(magHardwareToUse);