mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Reduce RAM usage of mpu6050 initialisation.
This commit is contained in:
parent
f5895b762f
commit
38dbe897d9
3 changed files with 30 additions and 26 deletions
|
@ -172,19 +172,19 @@ typedef enum {
|
||||||
|
|
||||||
static mpu6050Resolution_e mpuAccelTrim;
|
static mpu6050Resolution_e mpuAccelTrim;
|
||||||
|
|
||||||
static mpu6050Config_t *config = NULL;
|
static const mpu6050Config_t *mpu6050Config = NULL;
|
||||||
|
|
||||||
void mpu6050GpioInit(void) {
|
void mpu6050GpioInit(void) {
|
||||||
gpio_config_t gpio;
|
gpio_config_t gpio;
|
||||||
|
|
||||||
if (config->gpioAPB2Peripherals) {
|
if (mpu6050Config->gpioAPB2Peripherals) {
|
||||||
RCC_APB2PeriphClockCmd(config->gpioAPB2Peripherals, ENABLE);
|
RCC_APB2PeriphClockCmd(mpu6050Config->gpioAPB2Peripherals, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
gpio.pin = config->gpioPin;
|
gpio.pin = mpu6050Config->gpioPin;
|
||||||
gpio.speed = Speed_2MHz;
|
gpio.speed = Speed_2MHz;
|
||||||
gpio.mode = Mode_IN_FLOATING;
|
gpio.mode = Mode_IN_FLOATING;
|
||||||
gpioInit(config->gpioPort, &gpio);
|
gpioInit(mpu6050Config->gpioPort, &gpio);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool mpu6050Detect(void)
|
static bool mpu6050Detect(void)
|
||||||
|
@ -209,13 +209,13 @@ static bool mpu6050Detect(void)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool mpu6050AccDetect(mpu6050Config_t *configToUse, acc_t *acc)
|
bool mpu6050AccDetect(const mpu6050Config_t *configToUse, acc_t *acc)
|
||||||
{
|
{
|
||||||
uint8_t readBuffer[6];
|
uint8_t readBuffer[6];
|
||||||
uint8_t revision;
|
uint8_t revision;
|
||||||
uint8_t productId;
|
uint8_t productId;
|
||||||
|
|
||||||
config = configToUse;
|
mpu6050Config = configToUse;
|
||||||
|
|
||||||
if (!mpu6050Detect()) {
|
if (!mpu6050Detect()) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -255,9 +255,9 @@ bool mpu6050AccDetect(mpu6050Config_t *configToUse, acc_t *acc)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool mpu6050GyroDetect(mpu6050Config_t *configToUse, gyro_t *gyro, uint16_t lpf)
|
bool mpu6050GyroDetect(const mpu6050Config_t *configToUse, gyro_t *gyro, uint16_t lpf)
|
||||||
{
|
{
|
||||||
config = configToUse;
|
mpu6050Config = configToUse;
|
||||||
|
|
||||||
if (!mpu6050Detect()) {
|
if (!mpu6050Detect()) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -288,9 +288,9 @@ bool mpu6050GyroDetect(mpu6050Config_t *configToUse, gyro_t *gyro, uint16_t lpf)
|
||||||
|
|
||||||
static void mpu6050AccInit(void)
|
static void mpu6050AccInit(void)
|
||||||
{
|
{
|
||||||
if (config) {
|
if (mpu6050Config) {
|
||||||
mpu6050GpioInit();
|
mpu6050GpioInit();
|
||||||
config = NULL; // avoid re-initialisation of GPIO;
|
mpu6050Config = NULL; // avoid re-initialisation of GPIO;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (mpuAccelTrim) {
|
switch (mpuAccelTrim) {
|
||||||
|
@ -315,9 +315,9 @@ static void mpu6050AccRead(int16_t *accData)
|
||||||
|
|
||||||
static void mpu6050GyroInit(void)
|
static void mpu6050GyroInit(void)
|
||||||
{
|
{
|
||||||
if (config) {
|
if (mpu6050Config) {
|
||||||
mpu6050GpioInit();
|
mpu6050GpioInit();
|
||||||
config = NULL; // avoid re-initialisation of GPIO;
|
mpu6050Config = NULL; // avoid re-initialisation of GPIO;
|
||||||
}
|
}
|
||||||
|
|
||||||
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||||
|
|
|
@ -23,7 +23,7 @@ typedef struct mpu6050Config_s {
|
||||||
GPIO_TypeDef *gpioPort;
|
GPIO_TypeDef *gpioPort;
|
||||||
} mpu6050Config_t;
|
} mpu6050Config_t;
|
||||||
|
|
||||||
bool mpu6050AccDetect(mpu6050Config_t *config,acc_t *acc);
|
bool mpu6050AccDetect(const mpu6050Config_t *config,acc_t *acc);
|
||||||
bool mpu6050GyroDetect(mpu6050Config_t *config, gyro_t *gyro, uint16_t lpf);
|
bool mpu6050GyroDetect(const mpu6050Config_t *config, gyro_t *gyro, uint16_t lpf);
|
||||||
void mpu6050DmpLoop(void);
|
void mpu6050DmpLoop(void);
|
||||||
void mpu6050DmpResetFifo(void);
|
void mpu6050DmpResetFifo(void);
|
||||||
|
|
|
@ -67,23 +67,27 @@ extern gyro_t gyro;
|
||||||
extern baro_t baro;
|
extern baro_t baro;
|
||||||
extern acc_t acc;
|
extern acc_t acc;
|
||||||
|
|
||||||
mpu6050Config_t *generateMPU6050Config(void)
|
const mpu6050Config_t *selectMPU6050Config(void)
|
||||||
{
|
{
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
static mpu6050Config_t nazeMPU6050Config;
|
|
||||||
|
|
||||||
// MPU_INT output on rev4/5 hardware (PB13, PC13)
|
// MPU_INT output on rev4/5 hardware (PB13, PC13)
|
||||||
nazeMPU6050Config.gpioPin = Pin_13;
|
static const mpu6050Config_t nazeRev4MPU6050Config = {
|
||||||
|
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB,
|
||||||
|
.gpioPort = GPIOB,
|
||||||
|
.gpioPin = Pin_13
|
||||||
|
};
|
||||||
|
static const mpu6050Config_t nazeRev5MPU6050Config = {
|
||||||
|
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC,
|
||||||
|
.gpioPort = GPIOC,
|
||||||
|
.gpioPin = Pin_13
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
if (hardwareRevision < NAZE32_REV5) {
|
if (hardwareRevision < NAZE32_REV5) {
|
||||||
nazeMPU6050Config.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB;
|
return &nazeRev4MPU6050Config;
|
||||||
nazeMPU6050Config.gpioPort = GPIOB;
|
|
||||||
} else {
|
} else {
|
||||||
nazeMPU6050Config.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC;
|
return &nazeRev5MPU6050Config;
|
||||||
nazeMPU6050Config.gpioPort = GPIOC;
|
|
||||||
}
|
}
|
||||||
return &nazeMPU6050Config;
|
|
||||||
#endif
|
#endif
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
@ -127,7 +131,7 @@ bool detectGyro(uint16_t gyroLpf)
|
||||||
gyroAlign = ALIGN_DEFAULT;
|
gyroAlign = ALIGN_DEFAULT;
|
||||||
|
|
||||||
#ifdef USE_GYRO_MPU6050
|
#ifdef USE_GYRO_MPU6050
|
||||||
if (mpu6050GyroDetect(generateMPU6050Config(), &gyro, gyroLpf)) {
|
if (mpu6050GyroDetect(selectMPU6050Config(), &gyro, gyroLpf)) {
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
gyroAlign = CW0_DEG;
|
gyroAlign = CW0_DEG;
|
||||||
#endif
|
#endif
|
||||||
|
@ -231,7 +235,7 @@ retry:
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ACC_MPU6050
|
#ifdef USE_ACC_MPU6050
|
||||||
case ACC_MPU6050: // MPU6050
|
case ACC_MPU6050: // MPU6050
|
||||||
if (mpu6050AccDetect(generateMPU6050Config(), &acc)) {
|
if (mpu6050AccDetect(selectMPU6050Config(), &acc)) {
|
||||||
accHardware = ACC_MPU6050;
|
accHardware = ACC_MPU6050;
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
accAlign = CW0_DEG;
|
accAlign = CW0_DEG;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue