mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Deprecate gyro_sync_denom, gyro driver will make a decision about sampling rate at init
This commit is contained in:
parent
f393ecc651
commit
6ce5940e75
78 changed files with 885 additions and 306 deletions
24
Makefile
24
Makefile
|
@ -104,7 +104,7 @@ endif
|
|||
# silently ignore if the file is not present. Allows for target specific.
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
|
||||
|
||||
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS)
|
||||
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS)
|
||||
F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS)
|
||||
|
||||
ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
|
||||
|
@ -117,7 +117,7 @@ endif
|
|||
|
||||
128K_TARGETS = $(F1_TARGETS)
|
||||
256K_TARGETS = $(F3_TARGETS)
|
||||
512K_TARGETS = $(F411_TARGETS) $(F7X2RE_TARGETS) $(F7X5XE_TARGETS)
|
||||
512K_TARGETS = $(F411_TARGETS) $(F446_TARGETS) $(F7X2RE_TARGETS) $(F7X5XE_TARGETS)
|
||||
1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS) $(F7X6XG_TARGETS)
|
||||
2048K_TARGETS = $(F427_TARGETS) $(F7X5XI_TARGETS)
|
||||
|
||||
|
@ -253,6 +253,10 @@ ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS)))
|
|||
EXCLUDES += stm32f4xx_fsmc.c
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS)))
|
||||
EXCLUDES += stm32f4xx_fsmc.c
|
||||
endif
|
||||
|
||||
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
|
||||
|
||||
#USB
|
||||
|
@ -309,6 +313,10 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
|
|||
DEVICE_FLAGS = -DSTM32F40_41xxx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
|
||||
STARTUP_SRC = startup_stm32f40xx.s
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F446_TARGETS)))
|
||||
DEVICE_FLAGS = -DSTM32F446xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f446.ld
|
||||
STARTUP_SRC = startup_stm32f446xx.s
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F427_TARGETS)))
|
||||
DEVICE_FLAGS = -DSTM32F427_437xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f427.ld
|
||||
|
@ -316,6 +324,7 @@ STARTUP_SRC = startup_stm32f427xx.s
|
|||
else
|
||||
$(error Unknown MCU for F4 target)
|
||||
endif
|
||||
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
|
||||
|
||||
TARGET_FLAGS = -D$(TARGET)
|
||||
|
@ -575,7 +584,6 @@ COMMON_SRC = \
|
|||
drivers/display.c \
|
||||
drivers/exti.c \
|
||||
drivers/gps_i2cnav.c \
|
||||
drivers/gyro_sync.c \
|
||||
drivers/io.c \
|
||||
drivers/io_pca9685.c \
|
||||
drivers/light_led.c \
|
||||
|
@ -758,6 +766,7 @@ endif
|
|||
|
||||
STM32F10x_COMMON_SRC = \
|
||||
startup_stm32f10x_md_gcc.S \
|
||||
drivers/accgyro/accgyro.c \
|
||||
drivers/adc_stm32f10x.c \
|
||||
drivers/bus_i2c_stm32f10x.c \
|
||||
drivers/dma.c \
|
||||
|
@ -771,6 +780,7 @@ STM32F10x_COMMON_SRC = \
|
|||
STM32F30x_COMMON_SRC = \
|
||||
startup_stm32f30x_md_gcc.S \
|
||||
target/system_stm32f30x.c \
|
||||
drivers/accgyro/accgyro.c \
|
||||
drivers/adc_stm32f30x.c \
|
||||
drivers/bus_i2c_stm32f30x.c \
|
||||
drivers/dma.c \
|
||||
|
@ -781,6 +791,7 @@ STM32F30x_COMMON_SRC = \
|
|||
|
||||
STM32F4xx_COMMON_SRC = \
|
||||
target/system_stm32f4xx.c \
|
||||
drivers/accgyro/accgyro.c \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/adc_stm32f4xx.c \
|
||||
drivers/adc_stm32f4xx.c \
|
||||
|
@ -795,6 +806,7 @@ STM32F4xx_COMMON_SRC = \
|
|||
|
||||
STM32F7xx_COMMON_SRC = \
|
||||
target/system_stm32f7xx.c \
|
||||
drivers/accgyro/accgyro.c \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/adc_stm32f7xx.c \
|
||||
drivers/bus_i2c_hal.c \
|
||||
|
@ -1034,7 +1046,7 @@ targets-group-rest: $(GROUP_OTHER_TARGETS)
|
|||
$(VALID_TARGETS):
|
||||
$(V0) echo "" && \
|
||||
echo "Building $@" && \
|
||||
$(MAKE) -j 4 TARGET=$@ && \
|
||||
$(MAKE) -j 8 TARGET=$@ && \
|
||||
echo "Building $@ succeeded."
|
||||
|
||||
## clean : clean up all temporary / machine-generated files
|
||||
|
@ -1051,11 +1063,11 @@ clean_test:
|
|||
|
||||
## clean_<TARGET> : clean up one specific target
|
||||
$(CLEAN_TARGETS) :
|
||||
$(V0) $(MAKE) -j 4 TARGET=$(subst clean_,,$@) clean
|
||||
$(V0) $(MAKE) -j 8 TARGET=$(subst clean_,,$@) clean
|
||||
|
||||
## <TARGET>_clean : clean up one specific target (alias for above)
|
||||
$(TARGETS_CLEAN) :
|
||||
$(V0) $(MAKE) -j 4 TARGET=$(subst _clean,,$@) clean
|
||||
$(V0) $(MAKE) -j 8 TARGET=$(subst _clean,,$@) clean
|
||||
|
||||
## clean_all : clean all valid targets
|
||||
clean_all:$(CLEAN_TARGETS)
|
||||
|
|
|
@ -1381,7 +1381,6 @@ static bool blackboxWriteSysinfo(void)
|
|||
);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE("looptime", "%d", getPidUpdateRate());
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom", "%d", gyroConfig()->gyroSyncDenominator);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_rate", "%d", 100); //For compatibility reasons write rc_rate 100
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d", currentControlRateProfile->stabilized.rcExpo8);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_yaw_expo", "%d", currentControlRateProfile->stabilized.rcYawExpo8);
|
||||
|
|
|
@ -423,7 +423,6 @@ static const OSD_Entry cmsx_menuGyroEntries[] =
|
|||
OSD_LABEL_DATA_ENTRY("-- GYRO GLB --", profileIndexString),
|
||||
|
||||
OSD_SETTING_ENTRY("GYRO SYNC", SETTING_GYRO_SYNC),
|
||||
OSD_SETTING_ENTRY("GYRO DENOM", SETTING_GYRO_SYNC_DENOM),
|
||||
OSD_SETTING_ENTRY("GYRO LPF", SETTING_GYRO_HARDWARE_LPF),
|
||||
|
||||
OSD_BACK_ENTRY,
|
||||
|
|
|
@ -37,11 +37,13 @@ extern uint8_t __config_end;
|
|||
# define FLASH_PAGE_SIZE (0x800)
|
||||
// F4
|
||||
# elif defined(STM32F40_41xxx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
|
||||
# elif defined (STM32F411xE)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
|
||||
# elif defined(STM32F446xx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
|
||||
# elif defined(STM32F427_437xx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x20000) // 128K sectors
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
|
||||
// F7
|
||||
#elif defined(STM32F722xx)
|
||||
# define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
||||
|
|
127
src/main/drivers/accgyro/accgyro.c
Normal file
127
src/main/drivers/accgyro/accgyro.c
Normal file
|
@ -0,0 +1,127 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/atomic.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
|
||||
const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count)
|
||||
{
|
||||
int i;
|
||||
int8_t selectedLpf = configs[0].gyroLpf;
|
||||
const gyroFilterAndRateConfig_t * candidate = &configs[0];
|
||||
|
||||
// Choose closest supported LPF value
|
||||
for (i = 1; i < count; i++) {
|
||||
if (ABS(desiredLpf - configs[i].gyroLpf) < ABS(desiredLpf - selectedLpf)) {
|
||||
selectedLpf = configs[i].gyroLpf;
|
||||
candidate = &configs[i];
|
||||
}
|
||||
}
|
||||
|
||||
// Now find the closest update rate
|
||||
for (i = 0; i < count; i++) {
|
||||
if ((configs[i].gyroLpf == selectedLpf) && (ABS(desiredRateHz - candidate->gyroRateHz) > ABS(desiredRateHz - configs[i].gyroRateHz))) {
|
||||
candidate = &configs[i];
|
||||
}
|
||||
}
|
||||
|
||||
DEBUG_TRACE("GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X",
|
||||
desiredLpf, desiredRateHz,
|
||||
candidate->gyroLpf, candidate->gyroRateHz,
|
||||
candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]);
|
||||
|
||||
return candidate;
|
||||
}
|
||||
|
||||
/*
|
||||
* Gyro interrupt service routine
|
||||
*/
|
||||
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
|
||||
static void gyroIntExtiHandler(extiCallbackRec_t *cb)
|
||||
{
|
||||
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
|
||||
gyro->dataReady = true;
|
||||
if (gyro->updateFn) {
|
||||
gyro->updateFn(gyro);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void gyroIntExtiInit(gyroDev_t *gyro)
|
||||
{
|
||||
if (!gyro->busDev->irqPin) {
|
||||
return;
|
||||
}
|
||||
|
||||
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
|
||||
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
|
||||
uint8_t status = IORead(gyro->busDev->irqPin);
|
||||
if (status) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined (STM32F7)
|
||||
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
|
||||
EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);
|
||||
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
|
||||
#else
|
||||
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
IOConfigGPIO(gyro->busDev->irqPin, IOCFG_IN_FLOATING);
|
||||
|
||||
EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);
|
||||
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, EXTI_Trigger_Rising);
|
||||
EXTIEnable(gyro->busDev->irqPin, true);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
bool gyroCheckDataReady(gyroDev_t* gyro)
|
||||
{
|
||||
bool ret;
|
||||
if (gyro->dataReady) {
|
||||
ret = true;
|
||||
gyro->dataReady = false;
|
||||
} else {
|
||||
ret = false;
|
||||
}
|
||||
return ret;
|
||||
}
|
|
@ -21,7 +21,6 @@
|
|||
#include "common/axis.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
|
||||
#define GYRO_LPF_256HZ 0
|
||||
#define GYRO_LPF_188HZ 1
|
||||
|
@ -32,11 +31,11 @@
|
|||
#define GYRO_LPF_5HZ 6
|
||||
#define GYRO_LPF_NONE 7
|
||||
|
||||
typedef enum {
|
||||
GYRO_RATE_1_kHz,
|
||||
GYRO_RATE_8_kHz,
|
||||
GYRO_RATE_32_kHz,
|
||||
} gyroRateKHz_e;
|
||||
typedef struct {
|
||||
uint8_t gyroLpf;
|
||||
uint16_t gyroRateHz;
|
||||
uint8_t gyroConfigValues[2];
|
||||
} gyroFilterAndRateConfig_t;
|
||||
|
||||
typedef struct gyroDev_s {
|
||||
busDevice_t * busDev;
|
||||
|
@ -49,11 +48,11 @@ typedef struct gyroDev_s {
|
|||
float scale; // scalefactor
|
||||
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
|
||||
int16_t gyroZero[XYZ_AXIS_COUNT];
|
||||
uint8_t lpf;
|
||||
uint8_t imuSensorToUse;
|
||||
gyroRateKHz_e gyroRateKHz;
|
||||
uint8_t mpuDividerDrops;
|
||||
uint8_t lpf; // Configuration value: Hardware LPF setting
|
||||
uint32_t requestedSampleIntervalUs; // Requested sample interval
|
||||
volatile bool dataReady;
|
||||
uint32_t sampleRateIntervalUs; // Gyro driver should set this to actual sampling rate as signaled by IRQ
|
||||
sensor_align_e gyroAlign;
|
||||
} gyroDev_t;
|
||||
|
||||
|
@ -66,3 +65,7 @@ typedef struct accDev_s {
|
|||
uint8_t imuSensorToUse;
|
||||
sensor_align_e accAlign;
|
||||
} accDev_t;
|
||||
|
||||
const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count);
|
||||
void gyroIntExtiInit(struct gyroDev_s *gyro);
|
||||
bool gyroCheckDataReady(struct gyroDev_s *gyro);
|
||||
|
|
|
@ -45,48 +45,33 @@
|
|||
// Check busDevice scratchpad memory size
|
||||
STATIC_ASSERT(sizeof(mpuContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small);
|
||||
|
||||
/*
|
||||
* Gyro interrupt service routine
|
||||
*/
|
||||
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
|
||||
static void mpuIntExtiHandler(extiCallbackRec_t *cb)
|
||||
static const gyroFilterAndRateConfig_t mpuGyroConfigs[] = {
|
||||
{ GYRO_LPF_256HZ, 8000, { MPU_DLPF_256HZ, 0 } },
|
||||
{ GYRO_LPF_256HZ, 4000, { MPU_DLPF_256HZ, 1 } },
|
||||
{ GYRO_LPF_256HZ, 2000, { MPU_DLPF_256HZ, 3 } },
|
||||
{ GYRO_LPF_256HZ, 1000, { MPU_DLPF_256HZ, 7 } },
|
||||
{ GYRO_LPF_256HZ, 666, { MPU_DLPF_256HZ, 11 } },
|
||||
{ GYRO_LPF_256HZ, 500, { MPU_DLPF_256HZ, 15 } },
|
||||
|
||||
{ GYRO_LPF_188HZ, 1000, { MPU_DLPF_188HZ, 0 } },
|
||||
{ GYRO_LPF_188HZ, 500, { MPU_DLPF_188HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_98HZ, 1000, { MPU_DLPF_98HZ, 0 } },
|
||||
{ GYRO_LPF_98HZ, 500, { MPU_DLPF_98HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_42HZ, 1000, { MPU_DLPF_42HZ, 0 } },
|
||||
{ GYRO_LPF_42HZ, 500, { MPU_DLPF_42HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_20HZ, 1000, { MPU_DLPF_20HZ, 0 } },
|
||||
{ GYRO_LPF_20HZ, 500, { MPU_DLPF_20HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_10HZ, 1000, { MPU_DLPF_10HZ, 0 } },
|
||||
{ GYRO_LPF_10HZ, 500, { MPU_DLPF_10HZ, 1 } }
|
||||
};
|
||||
|
||||
const gyroFilterAndRateConfig_t * mpuChooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz)
|
||||
{
|
||||
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
|
||||
gyro->dataReady = true;
|
||||
if (gyro->updateFn) {
|
||||
gyro->updateFn(gyro);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void mpuIntExtiInit(gyroDev_t *gyro)
|
||||
{
|
||||
if (!gyro->busDev->irqPin) {
|
||||
return;
|
||||
}
|
||||
|
||||
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
|
||||
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
|
||||
uint8_t status = IORead(gyro->busDev->irqPin);
|
||||
if (status) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined (STM32F7)
|
||||
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
|
||||
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
|
||||
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
|
||||
#else
|
||||
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
IOConfigGPIO(gyro->busDev->irqPin, IOCFG_IN_FLOATING);
|
||||
|
||||
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
|
||||
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
|
||||
EXTIEnable(gyro->busDev->irqPin, true);
|
||||
#endif
|
||||
#endif
|
||||
return chooseGyroConfig(desiredLpf, desiredRateHz, &mpuGyroConfigs[0], ARRAYLEN(mpuGyroConfigs));
|
||||
}
|
||||
|
||||
bool mpuGyroRead(gyroDev_t *gyro)
|
||||
|
@ -105,18 +90,6 @@ bool mpuGyroRead(gyroDev_t *gyro)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool mpuCheckDataReady(gyroDev_t* gyro)
|
||||
{
|
||||
bool ret;
|
||||
if (gyro->dataReady) {
|
||||
ret = true;
|
||||
gyro->dataReady = false;
|
||||
} else {
|
||||
ret = false;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
static bool mpuUpdateSensorContext(busDevice_t * busDev, mpuContextData_t * ctx)
|
||||
{
|
||||
ctx->lastReadStatus = busReadBuf(busDev, MPU_RA_ACCEL_XOUT_H, ctx->accRaw, 6 + 2 + 6);
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
|
||||
#define MPU_I2C_ADDRESS 0x68
|
||||
|
||||
|
@ -130,6 +131,13 @@
|
|||
// RF = Register Flag
|
||||
#define MPU_RF_DATA_RDY_EN (1 << 0)
|
||||
|
||||
#define MPU_DLPF_10HZ 0x05
|
||||
#define MPU_DLPF_20HZ 0x04
|
||||
#define MPU_DLPF_42HZ 0x03
|
||||
#define MPU_DLPF_98HZ 0x02
|
||||
#define MPU_DLPF_188HZ 0x01
|
||||
#define MPU_DLPF_256HZ 0x00
|
||||
|
||||
typedef struct mpuConfiguration_s {
|
||||
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
|
||||
} mpuConfiguration_t;
|
||||
|
@ -173,11 +181,9 @@ enum accel_fsr_e {
|
|||
|
||||
struct gyroDev_s;
|
||||
struct accDev_s;
|
||||
void mpuIntExtiInit(struct gyroDev_s *gyro);
|
||||
|
||||
const gyroFilterAndRateConfig_t * mpuChooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz);
|
||||
bool mpuGyroRead(struct gyroDev_s *gyro);
|
||||
bool mpuGyroReadScratchpad(struct gyroDev_s *gyro);
|
||||
bool mpuAccReadScratchpad(struct accDev_s *acc);
|
||||
bool mpuTemperatureReadScratchpad(struct gyroDev_s *gyro, int16_t * data);
|
||||
|
||||
bool mpuCheckDataReady(struct gyroDev_s *gyro);
|
||||
|
|
|
@ -64,34 +64,22 @@ static void mpu3050Init(gyroDev_t *gyro)
|
|||
{
|
||||
bool ack;
|
||||
busDevice_t * busDev = gyro->busDev;
|
||||
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
|
||||
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
|
||||
|
||||
delay(25); // datasheet page 13 says 20ms. other stuff could have been running meanwhile. but we'll be safe
|
||||
|
||||
ack = busWrite(busDev, MPU3050_SMPLRT_DIV, 0);
|
||||
ack = busWrite(busDev, MPU3050_SMPLRT_DIV, config->gyroConfigValues[1]);
|
||||
if (!ack) {
|
||||
failureMode(FAILURE_ACC_INIT);
|
||||
}
|
||||
|
||||
busWrite(busDev, MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | gyro->lpf);
|
||||
busWrite(busDev, MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | config->gyroConfigValues[0]);
|
||||
busWrite(busDev, MPU3050_INT_CFG, 0);
|
||||
busWrite(busDev, MPU3050_USER_CTRL, MPU3050_USER_RESET);
|
||||
busWrite(busDev, MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
||||
}
|
||||
|
||||
/*
|
||||
static bool mpu3050ReadTemperature(gyroDev_t *gyro, int16_t *tempData)
|
||||
{
|
||||
uint8_t buf[2];
|
||||
if (!gyro->mpuConfiguration.readFn(&gyro->bus, MPU3050_TEMP_OUT, 2, buf)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
*tempData = 35 + ((int32_t)(buf[0] << 8 | buf[1]) + 13200) / 280;
|
||||
|
||||
return true;
|
||||
}
|
||||
*/
|
||||
|
||||
static bool mpu3050GyroRead(gyroDev_t *gyro)
|
||||
{
|
||||
uint8_t data[6];
|
||||
|
@ -129,7 +117,7 @@ static bool deviceDetect(busDevice_t * busDev)
|
|||
|
||||
bool mpu3050Detect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_MPU6000, gyro->imuSensorToUse, OWNER_MPU);
|
||||
gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_MPU3050, gyro->imuSensorToUse, OWNER_MPU);
|
||||
if (gyro->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
@ -141,7 +129,7 @@ bool mpu3050Detect(gyroDev_t *gyro)
|
|||
|
||||
gyro->initFn = mpu3050Init;
|
||||
gyro->readFn = mpu3050GyroRead;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
|
||||
return true;
|
||||
|
|
|
@ -37,8 +37,6 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
|
@ -74,7 +72,10 @@
|
|||
static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
busDevice_t * busDev = gyro->busDev;
|
||||
mpuIntExtiInit(gyro);
|
||||
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
|
||||
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
|
||||
|
||||
gyroIntExtiInit(gyro);
|
||||
|
||||
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
|
@ -98,7 +99,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
|
|||
|
||||
// Accel Sample Rate 1kHz
|
||||
// Gyroscope Output Rate = 1kHz when the DLPF is enabled
|
||||
busWrite(busDev, MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops(gyro));
|
||||
busWrite(busDev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]);
|
||||
delayMicroseconds(15);
|
||||
|
||||
// Gyro +/- 1000 DPS Full Scale
|
||||
|
@ -118,7 +119,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
|
|||
#endif
|
||||
|
||||
// Accel and Gyro DLPF Setting
|
||||
busWrite(busDev, MPU_RA_CONFIG, gyro->lpf);
|
||||
busWrite(busDev, MPU_RA_CONFIG, config->gyroConfigValues[0]);
|
||||
delayMicroseconds(1);
|
||||
|
||||
busSetSpeed(busDev, BUS_SPEED_FAST);
|
||||
|
@ -214,7 +215,7 @@ bool mpu6000GyroDetect(gyroDev_t *gyro)
|
|||
|
||||
gyro->initFn = mpu6000AccAndGyroInit;
|
||||
gyro->readFn = mpuGyroReadScratchpad;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->temperatureFn = mpuTemperatureReadScratchpad;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
|
||||
|
|
|
@ -37,8 +37,6 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
|
@ -60,7 +58,10 @@ static bool mpu6050InitDone = false;
|
|||
|
||||
static void mpu6050AccAndGyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
mpuIntExtiInit(gyro);
|
||||
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
|
||||
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
|
||||
|
||||
gyroIntExtiInit(gyro);
|
||||
|
||||
busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
|
@ -75,11 +76,11 @@ static void mpu6050AccAndGyroInit(gyroDev_t *gyro)
|
|||
|
||||
// Accel Sample Rate 1kHz
|
||||
// Gyroscope Output Rate = 1kHz when the DLPF is enabled
|
||||
busWrite(gyro->busDev, MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops(gyro));
|
||||
busWrite(gyro->busDev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]);
|
||||
delayMicroseconds(15);
|
||||
|
||||
// Accel and Gyro DLPF Setting
|
||||
busWrite(gyro->busDev, MPU_RA_CONFIG, gyro->lpf);
|
||||
busWrite(gyro->busDev, MPU_RA_CONFIG, config->gyroConfigValues[0]);
|
||||
delayMicroseconds(1);
|
||||
|
||||
// Gyro +/- 2000 DPS Full Scale
|
||||
|
@ -209,7 +210,7 @@ bool mpu6050GyroDetect(gyroDev_t *gyro)
|
|||
|
||||
gyro->initFn = mpu6050AccAndGyroInit;
|
||||
gyro->readFn = mpuGyroReadScratchpad;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->temperatureFn = mpuTemperatureReadScratchpad;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
|
||||
|
|
|
@ -28,7 +28,6 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
|
@ -69,7 +68,10 @@ bool mpu6500AccDetect(accDev_t *acc)
|
|||
static void mpu6500AccAndGyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
busDevice_t * dev = gyro->busDev;
|
||||
mpuIntExtiInit(gyro);
|
||||
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
|
||||
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
|
||||
|
||||
gyroIntExtiInit(gyro);
|
||||
|
||||
busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
|
@ -85,18 +87,16 @@ static void mpu6500AccAndGyroInit(gyroDev_t *gyro)
|
|||
busWrite(dev, MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
||||
delay(15);
|
||||
|
||||
const uint8_t raGyroConfigData = gyro->gyroRateKHz > GYRO_RATE_8_kHz ? (INV_FSR_2000DPS << 3 | FCB_3600_32) : (INV_FSR_2000DPS << 3 | FCB_DISABLED);
|
||||
|
||||
busWrite(dev, MPU_RA_GYRO_CONFIG, raGyroConfigData);
|
||||
busWrite(dev, MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED);
|
||||
delay(15);
|
||||
|
||||
busWrite(dev, MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
delay(15);
|
||||
|
||||
busWrite(dev, MPU_RA_CONFIG, gyro->lpf);
|
||||
busWrite(dev, MPU_RA_CONFIG, config->gyroConfigValues[0]);
|
||||
delay(15);
|
||||
|
||||
busWrite(dev, MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops(gyro)); // Get Divider
|
||||
busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]);
|
||||
delay(100);
|
||||
|
||||
// Data ready interrupt configuration
|
||||
|
@ -164,7 +164,7 @@ bool mpu6500GyroDetect(gyroDev_t *gyro)
|
|||
|
||||
gyro->initFn = mpu6500AccAndGyroInit;
|
||||
gyro->readFn = mpuGyroReadScratchpad;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->temperatureFn = mpuTemperatureReadScratchpad;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
|
||||
|
|
|
@ -28,7 +28,6 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
|
@ -69,7 +68,10 @@ bool mpu9250AccDetect(accDev_t *acc)
|
|||
static void mpu9250AccAndGyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
busDevice_t * dev = gyro->busDev;
|
||||
mpuIntExtiInit(gyro);
|
||||
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
|
||||
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
|
||||
|
||||
gyroIntExtiInit(gyro);
|
||||
|
||||
busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
|
@ -85,18 +87,16 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro)
|
|||
busWrite(dev, MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
||||
delay(15);
|
||||
|
||||
const uint8_t raGyroConfigData = gyro->gyroRateKHz > GYRO_RATE_8_kHz ? (INV_FSR_2000DPS << 3 | FCB_3600_32) : (INV_FSR_2000DPS << 3 | FCB_DISABLED);
|
||||
|
||||
busWrite(dev, MPU_RA_GYRO_CONFIG, raGyroConfigData);
|
||||
busWrite(dev, MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED);
|
||||
delay(15);
|
||||
|
||||
busWrite(dev, MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
delay(15);
|
||||
|
||||
busWrite(dev, MPU_RA_CONFIG, gyro->lpf);
|
||||
busWrite(dev, MPU_RA_CONFIG, config->gyroConfigValues[0]);
|
||||
delay(15);
|
||||
|
||||
busWrite(dev, MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops(gyro)); // Get Divider
|
||||
busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]);
|
||||
delay(100);
|
||||
|
||||
// Data ready interrupt configuration
|
||||
|
@ -161,7 +161,7 @@ bool mpu9250GyroDetect(gyroDev_t *gyro)
|
|||
|
||||
gyro->initFn = mpu9250AccAndGyroInit;
|
||||
gyro->readFn = mpuGyroReadScratchpad;
|
||||
gyro->intStatusFn = mpuCheckDataReady;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->temperatureFn = mpuTemperatureReadScratchpad;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
|
||||
|
|
|
@ -78,9 +78,11 @@ typedef enum {
|
|||
DEVHW_L3G4200,
|
||||
|
||||
/* Combined ACC/GYRO chips */
|
||||
DEVHW_MPU3050,
|
||||
DEVHW_MPU6000,
|
||||
DEVHW_MPU6050,
|
||||
DEVHW_MPU6500,
|
||||
DEVHW_BMI160,
|
||||
|
||||
/* Combined ACC/GYRO/MAG chips */
|
||||
DEVHW_MPU9250,
|
||||
|
|
|
@ -1,56 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
bool gyroSyncCheckIntStatus(gyroDev_t *gyro)
|
||||
{
|
||||
if (!gyro->intStatusFn)
|
||||
return false;
|
||||
return gyro->intStatusFn(gyro);
|
||||
}
|
||||
|
||||
uint32_t gyroSetSampleRate(gyroDev_t *gyro, uint32_t looptime, uint8_t lpf, uint8_t gyroSync, uint8_t gyroSyncDenominator)
|
||||
{
|
||||
if (gyroSync) {
|
||||
int gyroSamplePeriod;
|
||||
if (lpf == 0) {
|
||||
gyroSamplePeriod = 125;
|
||||
|
||||
} else {
|
||||
gyroSamplePeriod = 1000;
|
||||
}
|
||||
|
||||
gyro->mpuDividerDrops = gyroSyncDenominator - 1;
|
||||
looptime = gyroSyncDenominator * gyroSamplePeriod;
|
||||
} else {
|
||||
gyro->mpuDividerDrops = 0;
|
||||
}
|
||||
return looptime;
|
||||
}
|
||||
|
||||
uint8_t gyroMPU6xxxGetDividerDrops(const gyroDev_t *gyro)
|
||||
{
|
||||
return gyro->mpuDividerDrops;
|
||||
}
|
|
@ -1,22 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
|
||||
bool gyroSyncCheckIntStatus(gyroDev_t *gyro);
|
||||
uint8_t gyroMPU6xxxGetDividerDrops(const gyroDev_t *gyro);
|
||||
uint32_t gyroSetSampleRate(gyroDev_t *gyro, uint32_t looptime, uint8_t lpf, uint8_t gyroSync, uint8_t gyroSyncDenominator);
|
|
@ -8,7 +8,7 @@
|
|||
#define NVIC_PRIO_BARO_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||
#define NVIC_PRIO_SONAR_EXTI NVIC_BUILD_PRIORITY(2, 0) // maybe increate slightly
|
||||
#define NVIC_PRIO_TRANSPONDER_DMA NVIC_BUILD_PRIORITY(3, 0)
|
||||
#define NVIC_PRIO_MPU_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||
#define NVIC_PRIO_GYRO_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||
#define NVIC_PRIO_MAG_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
|
||||
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1)
|
||||
|
|
|
@ -75,7 +75,7 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|||
#if defined (STM32F411xE)
|
||||
UNUSED(tim);
|
||||
return 1;
|
||||
#elif defined (STM32F40_41xxx) || defined (STM32F427_437xx)
|
||||
#elif defined (STM32F40_41xxx) || defined (STM32F427_437xx) || defined (STM32F446xx)
|
||||
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
||||
return 1;
|
||||
} else {
|
||||
|
|
|
@ -167,7 +167,7 @@ static const char * const featureNames[] = {
|
|||
|
||||
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
|
||||
// sync with gyroSensor_e
|
||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE"};
|
||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"};
|
||||
|
||||
// sync this with sensors_e
|
||||
static const char * const sensorTypeNames[] = {
|
||||
|
|
|
@ -168,6 +168,7 @@ timeDelta_t getGyroUpdateRate(void)
|
|||
{
|
||||
return gyro.targetLooptime;
|
||||
}
|
||||
|
||||
uint16_t getAccUpdateRate(void)
|
||||
{
|
||||
#ifdef USE_ASYNC_GYRO_PROCESSING
|
||||
|
|
|
@ -32,7 +32,6 @@
|
|||
#include "common/filter.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
|
|
|
@ -49,7 +49,6 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/inverter.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
|
@ -72,7 +71,6 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/vcd.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
|
|
|
@ -1004,7 +1004,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
|
||||
case MSP_ADVANCED_CONFIG:
|
||||
sbufWriteU8(dst, gyroConfig()->gyroSyncDenominator);
|
||||
sbufWriteU8(dst, 1); // gyroConfig()->gyroSyncDenominator
|
||||
sbufWriteU8(dst, 1); // BF: masterConfig.pid_process_denom
|
||||
sbufWriteU8(dst, 1); // BF: motorConfig()->useUnsyncedPwm
|
||||
sbufWriteU8(dst, motorConfig()->motorPwmProtocol);
|
||||
|
@ -1737,7 +1737,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
|
||||
case MSP_SET_ADVANCED_CONFIG:
|
||||
if (dataSize >= 9) {
|
||||
gyroConfigMutable()->gyroSyncDenominator = sbufReadU8(src);
|
||||
sbufReadU8(src); // gyroConfig()->gyroSyncDenominator
|
||||
sbufReadU8(src); // BF: masterConfig.pid_process_denom
|
||||
sbufReadU8(src); // BF: motorConfig()->useUnsyncedPwm
|
||||
motorConfigMutable()->motorPwmProtocol = sbufReadU8(src);
|
||||
|
|
|
@ -4,7 +4,7 @@ tables:
|
|||
- name: gyro_lpf
|
||||
values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"]
|
||||
- name: acc_hardware
|
||||
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "FAKE"]
|
||||
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"]
|
||||
enum: accelerationSensor_e
|
||||
- name: rangefinder_hardware
|
||||
values: ["NONE", "HCSR04", "SRF10", "HCSR04I2C", "VL53L0X", "UIB"]
|
||||
|
@ -101,10 +101,6 @@ groups:
|
|||
- name: gyro_sync
|
||||
field: gyroSync
|
||||
type: bool
|
||||
- name: gyro_sync_denom
|
||||
field: gyroSyncDenominator
|
||||
min: 1
|
||||
max: 32
|
||||
- name: align_gyro
|
||||
field: gyro_align
|
||||
type: uint8_t
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
|
||||
#define STM32F7
|
||||
|
||||
#elif defined(STM32F40_41xxx) || defined (STM32F411xE) || defined (STM32F427_437xx)
|
||||
#elif defined(STM32F40_41xxx) || defined (STM32F411xE) || defined (STM32F427_437xx) || defined (STM32F446xx)
|
||||
#include "stm32f4xx_conf.h"
|
||||
#include "stm32f4xx_rcc.h"
|
||||
#include "stm32f4xx_gpio.h"
|
||||
|
|
|
@ -34,19 +34,19 @@
|
|||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6000.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6500.h"
|
||||
#include "drivers/accgyro/accgyro_mpu9250.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro/accgyro_bma280.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
#include "drivers/accgyro/accgyro_l3g4200d.h"
|
||||
#include "drivers/accgyro/accgyro_l3gd20.h"
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
#include "drivers/accgyro/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro/accgyro_mma845x.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
#include "drivers/accgyro/accgyro_bma280.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
|
|
|
@ -35,20 +35,19 @@
|
|||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6000.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6500.h"
|
||||
#include "drivers/accgyro/accgyro_mpu9250.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
#include "drivers/accgyro/accgyro_l3g4200d.h"
|
||||
#include "drivers/accgyro/accgyro_l3gd20.h"
|
||||
#include "drivers/accgyro/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro/accgyro_mma845x.h"
|
||||
#include "drivers/accgyro/accgyro_bma280.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
#include "drivers/accgyro/accgyro_l3g4200d.h"
|
||||
#include "drivers/accgyro/accgyro_mma845x.h"
|
||||
#include "drivers/accgyro/accgyro_l3gd20.h"
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/logging.h"
|
||||
|
||||
|
@ -97,13 +96,12 @@ STATIC_FASTRAM void *notchFilter2[XYZ_AXIS_COUNT];
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 2);
|
||||
|
||||
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
|
||||
.gyro_lpf = GYRO_LPF_42HZ, // INV_FILTER_42HZ, In case of ST gyro, will default to 32Hz instead
|
||||
.gyro_lpf = GYRO_LPF_42HZ, // 42HZ value is defined for Invensense/TDK gyros
|
||||
.gyro_soft_lpf_hz = 60,
|
||||
.gyro_align = ALIGN_DEFAULT,
|
||||
.gyroMovementCalibrationThreshold = 32,
|
||||
.looptime = 2000,
|
||||
.looptime = 1000,
|
||||
.gyroSync = 0,
|
||||
.gyroSyncDenominator = 2,
|
||||
.gyro_to_use = 0,
|
||||
.gyro_soft_notch_hz_1 = 0,
|
||||
.gyro_soft_notch_cutoff_1 = 1,
|
||||
|
@ -241,17 +239,19 @@ bool gyroInit(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
// After refactoring this function is always called after gyro sampling rate is known, so
|
||||
// no additional condition is required
|
||||
// Set gyro sample rate before driver initialisation
|
||||
// Driver initialisation
|
||||
gyroDev0.lpf = gyroConfig()->gyro_lpf;
|
||||
gyro.targetLooptime = gyroSetSampleRate(&gyroDev0, gyroConfig()->looptime, gyroConfig()->gyro_lpf, gyroConfig()->gyroSync, gyroConfig()->gyroSyncDenominator);
|
||||
// driver initialisation
|
||||
gyroDev0.requestedSampleIntervalUs = gyroConfig()->looptime;
|
||||
gyroDev0.sampleRateIntervalUs = gyroConfig()->looptime;
|
||||
gyroDev0.initFn(&gyroDev0);
|
||||
|
||||
// initFn will initialize sampleRateIntervalUs to actual gyro sampling rate (if driver supports it). Calculate target looptime using that value
|
||||
gyro.targetLooptime = gyroConfig()->gyroSync ? gyroDev0.sampleRateIntervalUs : gyroConfig()->looptime;
|
||||
|
||||
if (gyroConfig()->gyro_align != ALIGN_DEFAULT) {
|
||||
gyroDev0.gyroAlign = gyroConfig()->gyro_align;
|
||||
}
|
||||
|
||||
gyroInitFilters();
|
||||
return true;
|
||||
}
|
||||
|
@ -462,5 +462,8 @@ int16_t gyroRateDps(int axis)
|
|||
|
||||
bool gyroSyncCheckUpdate(void)
|
||||
{
|
||||
return gyroSyncCheckIntStatus(&gyroDev0);
|
||||
if (!gyroDev0.intStatusFn)
|
||||
return false;
|
||||
|
||||
return gyroDev0.intStatusFn(&gyroDev0);
|
||||
}
|
||||
|
|
|
@ -47,7 +47,7 @@ extern gyro_t gyro;
|
|||
typedef struct gyroConfig_s {
|
||||
sensor_align_e gyro_align; // gyro alignment
|
||||
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
|
||||
uint8_t gyroSyncDenominator; // Gyro sync Denominator
|
||||
uint8_t __deprecated_0; // Was: gyro sync denominator
|
||||
uint8_t gyroSync; // Enable interrupt based loop
|
||||
uint16_t looptime; // imu loop time in us
|
||||
uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
||||
|
|
506
src/main/startup/startup_stm32f446xx.s
Normal file
506
src/main/startup/startup_stm32f446xx.s
Normal file
|
@ -0,0 +1,506 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file startup_stm32f40_41xxx.s
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @brief STM32F40xxx/41xxx Devices vector table for Atollic TrueSTUDIO toolchain.
|
||||
* Same as startup_stm32f40_41xxx.s and maintained for legacy purpose
|
||||
* This module performs:
|
||||
* - Set the initial SP
|
||||
* - Set the initial PC == Reset_Handler,
|
||||
* - Set the vector table entries with the exceptions ISR address
|
||||
* - Configure the clock system and the external SRAM mounted on
|
||||
* STM324xG-EVAL board to be used as data memory (optional,
|
||||
* to be enabled by user)
|
||||
* - Branches to main in the C library (which eventually
|
||||
* calls main()).
|
||||
* After Reset the Cortex-M4 processor is in Thread mode,
|
||||
* priority is Privileged, and the Stack is set to Main.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
.syntax unified
|
||||
.cpu cortex-m4
|
||||
.fpu softvfp
|
||||
.thumb
|
||||
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
.word _sidata
|
||||
/* start address for the .data section. defined in linker script */
|
||||
.word _sdata
|
||||
/* end address for the .data section. defined in linker script */
|
||||
.word _edata
|
||||
/* start address for the .bss section. defined in linker script */
|
||||
.word _sbss
|
||||
/* end address for the .bss section. defined in linker script */
|
||||
.word _ebss
|
||||
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor first
|
||||
* starts execution following a reset event. Only the absolutely
|
||||
* necessary set is performed, after which the application
|
||||
* supplied main() routine is called.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
|
||||
.section .text.Reset_Handler
|
||||
.weak Reset_Handler
|
||||
.type Reset_Handler, %function
|
||||
|
||||
Reset_Handler:
|
||||
ldr sp, =_estack /* set stack pointer */
|
||||
|
||||
// Enable CCM
|
||||
// RCC->AHB1ENR |= RCC_AHB1ENR_CCMDATARAMEN;
|
||||
ldr r0, =0x40023800 // RCC_BASE
|
||||
ldr r1, [r0, #0x30] // AHB1ENR
|
||||
orr r1, r1, 0x00100000 // RCC_AHB1ENR_CCMDATARAMEN
|
||||
str r1, [r0, #0x30]
|
||||
dsb
|
||||
|
||||
// Check for bootloader reboot
|
||||
ldr r0, =0x2001FFFC // mj666
|
||||
ldr r1, =0xDEADBEEF // mj666
|
||||
ldr r2, [r0, #0] // mj666
|
||||
str r0, [r0, #0] // mj666
|
||||
cmp r2, r1 // mj666
|
||||
beq Reboot_Loader // mj666
|
||||
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
|
||||
CopyDataInit:
|
||||
ldr r3, =_sidata
|
||||
ldr r3, [r3, r1]
|
||||
str r3, [r0, r1]
|
||||
adds r1, r1, #4
|
||||
|
||||
LoopCopyDataInit:
|
||||
ldr r0, =_sdata
|
||||
ldr r3, =_edata
|
||||
adds r2, r0, r1
|
||||
cmp r2, r3
|
||||
bcc CopyDataInit
|
||||
ldr r2, =_sbss
|
||||
b LoopFillZerobss
|
||||
/* Zero fill the bss segment. */
|
||||
FillZerobss:
|
||||
movs r3, #0
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillZerobss:
|
||||
ldr r3, = _ebss
|
||||
cmp r2, r3
|
||||
bcc FillZerobss
|
||||
|
||||
/* Zero fill FASTRAM */
|
||||
ldr r2, =__fastram_bss_start__
|
||||
b LoopFillZeroFASTRAM
|
||||
|
||||
FillZeroFASTRAM:
|
||||
movs r3, #0
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillZeroFASTRAM:
|
||||
ldr r3, = __fastram_bss_end__
|
||||
cmp r2, r3
|
||||
bcc FillZeroFASTRAM
|
||||
|
||||
/* Mark the heap and stack */
|
||||
ldr r2, =_heap_stack_begin
|
||||
b LoopMarkHeapStack
|
||||
|
||||
MarkHeapStack:
|
||||
movs r3, 0xa5a5a5a5
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopMarkHeapStack:
|
||||
ldr r3, = _heap_stack_end
|
||||
cmp r2, r3
|
||||
bcc MarkHeapStack
|
||||
|
||||
/*FPU settings*/
|
||||
ldr r0, =0xE000ED88 /* Enable CP10,CP11 */
|
||||
ldr r1,[r0]
|
||||
orr r1,r1,#(0xF << 20)
|
||||
str r1,[r0]
|
||||
|
||||
/* Call the clock system intitialization function.*/
|
||||
bl SystemInit
|
||||
|
||||
/* Call the application entry point.*/
|
||||
bl main
|
||||
bx lr
|
||||
|
||||
LoopForever:
|
||||
b LoopForever
|
||||
|
||||
Reboot_Loader: // mj666
|
||||
|
||||
// Reboot to ROM // mj666
|
||||
ldr r0, =0x1FFF0000 // mj666
|
||||
ldr sp,[r0, #0] // mj666
|
||||
ldr r0,[r0, #4] // mj666
|
||||
bx r0 // mj666
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
Infinite_Loop:
|
||||
b Infinite_Loop
|
||||
.size Default_Handler, .-Default_Handler
|
||||
/******************************************************************************
|
||||
*
|
||||
* The minimal vector table for a Cortex M4. Note that the proper constructs
|
||||
* must be placed on this to ensure that it ends up at physical address
|
||||
* 0x0000.0000.
|
||||
*
|
||||
*******************************************************************************/
|
||||
.section .isr_vector,"a",%progbits
|
||||
.type g_pfnVectors, %object
|
||||
.size g_pfnVectors, .-g_pfnVectors
|
||||
|
||||
|
||||
g_pfnVectors:
|
||||
.word _estack
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
.word MemManage_Handler
|
||||
.word BusFault_Handler
|
||||
.word UsageFault_Handler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word SVC_Handler
|
||||
.word DebugMon_Handler
|
||||
.word 0
|
||||
.word PendSV_Handler
|
||||
.word SysTick_Handler
|
||||
|
||||
/* External Interrupts */
|
||||
.word WWDG_IRQHandler /* Window WatchDog */
|
||||
.word PVD_IRQHandler /* PVD through EXTI Line detection */
|
||||
.word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */
|
||||
.word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */
|
||||
.word FLASH_IRQHandler /* FLASH */
|
||||
.word RCC_IRQHandler /* RCC */
|
||||
.word EXTI0_IRQHandler /* EXTI Line0 */
|
||||
.word EXTI1_IRQHandler /* EXTI Line1 */
|
||||
.word EXTI2_IRQHandler /* EXTI Line2 */
|
||||
.word EXTI3_IRQHandler /* EXTI Line3 */
|
||||
.word EXTI4_IRQHandler /* EXTI Line4 */
|
||||
.word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */
|
||||
.word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */
|
||||
.word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */
|
||||
.word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */
|
||||
.word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */
|
||||
.word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */
|
||||
.word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */
|
||||
.word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */
|
||||
.word 0 /* CAN1 TX */
|
||||
.word 0 /* CAN1 RX0 */
|
||||
.word 0 /* CAN1 RX1 */
|
||||
.word 0 /* CAN1 SCE */
|
||||
.word EXTI9_5_IRQHandler /* External Line[9:5]s */
|
||||
.word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */
|
||||
.word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */
|
||||
.word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */
|
||||
.word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
|
||||
.word TIM2_IRQHandler /* TIM2 */
|
||||
.word TIM3_IRQHandler /* TIM3 */
|
||||
.word TIM4_IRQHandler /* TIM4 */
|
||||
.word I2C1_EV_IRQHandler /* I2C1 Event */
|
||||
.word I2C1_ER_IRQHandler /* I2C1 Error */
|
||||
.word I2C2_EV_IRQHandler /* I2C2 Event */
|
||||
.word I2C2_ER_IRQHandler /* I2C2 Error */
|
||||
.word SPI1_IRQHandler /* SPI1 */
|
||||
.word SPI2_IRQHandler /* SPI2 */
|
||||
.word USART1_IRQHandler /* USART1 */
|
||||
.word USART2_IRQHandler /* USART2 */
|
||||
.word 0 /* USART3 */
|
||||
.word EXTI15_10_IRQHandler /* External Line[15:10]s */
|
||||
.word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */
|
||||
.word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */
|
||||
.word 0 /* TIM8 Break and TIM12 */
|
||||
.word 0 /* TIM8 Update and TIM13 */
|
||||
.word 0 /* TIM8 Trigger and Commutation and TIM14 */
|
||||
.word 0 /* TIM8 Capture Compare */
|
||||
.word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */
|
||||
.word 0 /* FSMC */
|
||||
.word SDIO_IRQHandler /* SDIO */
|
||||
.word TIM5_IRQHandler /* TIM5 */
|
||||
.word SPI3_IRQHandler /* SPI3 */
|
||||
.word 0 /* UART4 */
|
||||
.word 0 /* UART5 */
|
||||
.word 0 /* TIM6 and DAC1&2 underrun errors */
|
||||
.word 0 /* TIM7 */
|
||||
.word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */
|
||||
.word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */
|
||||
.word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */
|
||||
.word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */
|
||||
.word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */
|
||||
.word 0 /* Ethernet */
|
||||
.word 0 /* Ethernet Wakeup through EXTI line */
|
||||
.word 0 /* CAN2 TX */
|
||||
.word 0 /* CAN2 RX0 */
|
||||
.word 0 /* CAN2 RX1 */
|
||||
.word 0 /* CAN2 SCE */
|
||||
.word OTG_FS_IRQHandler /* USB OTG FS */
|
||||
.word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */
|
||||
.word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */
|
||||
.word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */
|
||||
.word USART6_IRQHandler /* USART6 */
|
||||
.word I2C3_EV_IRQHandler /* I2C3 event */
|
||||
.word I2C3_ER_IRQHandler /* I2C3 error */
|
||||
.word 0 /* USB OTG HS End Point 1 Out */
|
||||
.word 0 /* USB OTG HS End Point 1 In */
|
||||
.word 0 /* USB OTG HS Wakeup through EXTI */
|
||||
.word 0 /* USB OTG HS */
|
||||
.word 0 /* DCMI */
|
||||
.word 0 /* CRYP crypto */
|
||||
.word 0 /* Hash and Rng */
|
||||
.word FPU_IRQHandler /* FPU */
|
||||
.word 0 /* Reserved */
|
||||
.word 0 /* Reserved */
|
||||
.word SPI4_IRQHandler /* SPI4 */
|
||||
.word SPI5_IRQHandler /* SPI5 */
|
||||
/*******************************************************************************
|
||||
*
|
||||
* Provide weak aliases for each Exception handler to the Default_Handler.
|
||||
* As they are weak aliases, any function with the same name will override
|
||||
* this definition.
|
||||
*
|
||||
*******************************************************************************/
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
.weak HardFault_Handler
|
||||
.thumb_set HardFault_Handler,Default_Handler
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
.weak UsageFault_Handler
|
||||
.thumb_set UsageFault_Handler,Default_Handler
|
||||
|
||||
.weak SVC_Handler
|
||||
.thumb_set SVC_Handler,Default_Handler
|
||||
|
||||
.weak DebugMon_Handler
|
||||
.thumb_set DebugMon_Handler,Default_Handler
|
||||
|
||||
.weak PendSV_Handler
|
||||
.thumb_set PendSV_Handler,Default_Handler
|
||||
|
||||
.weak SysTick_Handler
|
||||
.thumb_set SysTick_Handler,Default_Handler
|
||||
|
||||
.weak WWDG_IRQHandler
|
||||
.thumb_set WWDG_IRQHandler,Default_Handler
|
||||
|
||||
.weak PVD_IRQHandler
|
||||
.thumb_set PVD_IRQHandler,Default_Handler
|
||||
|
||||
.weak TAMP_STAMP_IRQHandler
|
||||
.thumb_set TAMP_STAMP_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_WKUP_IRQHandler
|
||||
.thumb_set RTC_WKUP_IRQHandler,Default_Handler
|
||||
|
||||
.weak FLASH_IRQHandler
|
||||
.thumb_set FLASH_IRQHandler,Default_Handler
|
||||
|
||||
.weak RCC_IRQHandler
|
||||
.thumb_set RCC_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI0_IRQHandler
|
||||
.thumb_set EXTI0_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI1_IRQHandler
|
||||
.thumb_set EXTI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI2_IRQHandler
|
||||
.thumb_set EXTI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI3_IRQHandler
|
||||
.thumb_set EXTI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI4_IRQHandler
|
||||
.thumb_set EXTI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream0_IRQHandler
|
||||
.thumb_set DMA1_Stream0_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream1_IRQHandler
|
||||
.thumb_set DMA1_Stream1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream2_IRQHandler
|
||||
.thumb_set DMA1_Stream2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream3_IRQHandler
|
||||
.thumb_set DMA1_Stream3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream4_IRQHandler
|
||||
.thumb_set DMA1_Stream4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream5_IRQHandler
|
||||
.thumb_set DMA1_Stream5_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream6_IRQHandler
|
||||
.thumb_set DMA1_Stream6_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC_IRQHandler
|
||||
.thumb_set ADC_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI9_5_IRQHandler
|
||||
.thumb_set EXTI9_5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_BRK_TIM9_IRQHandler
|
||||
.thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_UP_TIM10_IRQHandler
|
||||
.thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_TRG_COM_TIM11_IRQHandler
|
||||
.thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_CC_IRQHandler
|
||||
.thumb_set TIM1_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM2_IRQHandler
|
||||
.thumb_set TIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM3_IRQHandler
|
||||
.thumb_set TIM3_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM4_IRQHandler
|
||||
.thumb_set TIM4_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_EV_IRQHandler
|
||||
.thumb_set I2C1_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_ER_IRQHandler
|
||||
.thumb_set I2C1_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_EV_IRQHandler
|
||||
.thumb_set I2C2_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_ER_IRQHandler
|
||||
.thumb_set I2C2_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI1_IRQHandler
|
||||
.thumb_set SPI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI2_IRQHandler
|
||||
.thumb_set SPI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART1_IRQHandler
|
||||
.thumb_set USART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART2_IRQHandler
|
||||
.thumb_set USART2_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI15_10_IRQHandler
|
||||
.thumb_set EXTI15_10_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_Alarm_IRQHandler
|
||||
.thumb_set RTC_Alarm_IRQHandler,Default_Handler
|
||||
|
||||
.weak OTG_FS_WKUP_IRQHandler
|
||||
.thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Stream7_IRQHandler
|
||||
.thumb_set DMA1_Stream7_IRQHandler,Default_Handler
|
||||
|
||||
.weak SDIO_IRQHandler
|
||||
.thumb_set SDIO_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM5_IRQHandler
|
||||
.thumb_set TIM5_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI3_IRQHandler
|
||||
.thumb_set SPI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream0_IRQHandler
|
||||
.thumb_set DMA2_Stream0_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream1_IRQHandler
|
||||
.thumb_set DMA2_Stream1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream2_IRQHandler
|
||||
.thumb_set DMA2_Stream2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream3_IRQHandler
|
||||
.thumb_set DMA2_Stream3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream4_IRQHandler
|
||||
.thumb_set DMA2_Stream4_IRQHandler,Default_Handler
|
||||
|
||||
.weak OTG_FS_IRQHandler
|
||||
.thumb_set OTG_FS_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream5_IRQHandler
|
||||
.thumb_set DMA2_Stream5_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream6_IRQHandler
|
||||
.thumb_set DMA2_Stream6_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Stream7_IRQHandler
|
||||
.thumb_set DMA2_Stream7_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART6_IRQHandler
|
||||
.thumb_set USART6_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C3_EV_IRQHandler
|
||||
.thumb_set I2C3_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C3_ER_IRQHandler
|
||||
.thumb_set I2C3_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak FPU_IRQHandler
|
||||
.thumb_set FPU_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI4_IRQHandler
|
||||
.thumb_set SPI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI5_IRQHandler
|
||||
.thumb_set SPI5_IRQHandler,Default_Handler
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -33,7 +33,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU INT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
// MPU interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC14
|
||||
#define GYRO_INT_EXTI PC14
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
|
||||
// MPU interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC14
|
||||
#define GYRO_INT_EXTI PC14
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_EXTI
|
||||
|
||||
#define USE_MAG
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_EXTI
|
||||
|
||||
#define USE_MAG
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
|
||||
// ICM20689 interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA8
|
||||
#define GYRO_INT_EXTI PA8
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_EXTI
|
||||
|
||||
//#define USE_ESC_SENSOR // XXX
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_BARO
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
// MPU6500 interrupt
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_INT_EXTI PC5
|
||||
#define GYRO_INT_EXTI PC5
|
||||
#define MPU6500_CS_PIN PC4
|
||||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define BEEPER_OPT PB2
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA3
|
||||
#define GYRO_INT_EXTI PA3
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_SPI
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
|
||||
// MPU6 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_BARO
|
||||
|
|
|
@ -49,7 +49,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC0
|
||||
#define GYRO_INT_EXTI PC0
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_MAG
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
// MPU6500 interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA5
|
||||
#define GYRO_INT_EXTI PA5
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_INT_EXTI PB0
|
||||
#define GYRO_INT_EXTI PB0
|
||||
#define USE_EXTI
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
|
|
|
@ -61,7 +61,6 @@ void targetConfiguration(void)
|
|||
|
||||
gyroConfigMutable()->looptime = 1000;
|
||||
gyroConfigMutable()->gyroSync = 1;
|
||||
gyroConfigMutable()->gyroSyncDenominator = 8;
|
||||
gyroConfigMutable()->gyro_lpf = 0; // 256 Hz
|
||||
gyroConfigMutable()->gyro_soft_lpf_hz = 90;
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_1 = 150;
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PB0
|
||||
#define GYRO_INT_EXTI PB0
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
|
||||
// MPU interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define MPU9250_CS_PIN PC0
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
/*------------SENSORS--------------*/
|
||||
// MPU interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
/*------------SENSORS--------------*/
|
||||
// MPU interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
|
||||
// MPU6500 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_ADDRESS 0x69
|
||||
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_BARO
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#define INVERTER_PIN_UART3 PB15
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC5
|
||||
#define GYRO_INT_EXTI PC5
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define MPU6500_CS_PIN PC4
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC5
|
||||
#define GYRO_INT_EXTI PC5
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MPU_INT_EXTI PA4
|
||||
#define GYRO_INT_EXTI PA4
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_MPU6000
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
// MPU6500 interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA5
|
||||
#define GYRO_INT_EXTI PA5
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC3
|
||||
#define GYRO_INT_EXTI PC3
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC3
|
||||
#define GYRO_INT_EXTI PC3
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
|
||||
// MPU6050 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA15
|
||||
#define GYRO_INT_EXTI PA15
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
#define INVERTER_PIN_UART2 PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MAG_INT_EXTI PC14
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
#define USE_GYRO_MPU6000
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define GYRO_MPU6000_ALIGN CW90_DEG
|
||||
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA15
|
||||
#define GYRO_INT_EXTI PA15
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA15
|
||||
#define GYRO_INT_EXTI PA15
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_GYRO
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
|
||||
// MPU6050 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA15
|
||||
#define GYRO_INT_EXTI PA15
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
|
||||
#define MPU9250_SPI_BUS BUS_SPI1
|
||||
#define MPU9250_CS_PIN PC4
|
||||
#define MPU_INT_EXTI PC5
|
||||
#define GYRO_INT_EXTI PC5
|
||||
|
||||
#define USE_MAG
|
||||
#define USE_MAG_MPU9250
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
#define INVERTER_PIN_UART2 PB2
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
#define INVERTER_PIN_UART6 PB15
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
|
||||
// Gyro interrupt
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC4
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
|
|
|
@ -21,8 +21,8 @@
|
|||
|
||||
#if !defined(USE_TARGET_HARDWARE_DESCRIPTORS)
|
||||
|
||||
#if !defined(MPU_INT_EXTI)
|
||||
#define MPU_INT_EXTI NONE
|
||||
#if !defined(GYRO_INT_EXTI)
|
||||
#define GYRO_INT_EXTI NONE
|
||||
#endif
|
||||
|
||||
#if !defined(MPU_ADDRESS)
|
||||
|
@ -38,26 +38,34 @@
|
|||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU6000)
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU_INT_EXTI, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU6050)
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu6050, DEVHW_MPU6050, MPU6050_I2C_BUS, MPU_ADDRESS, MPU_INT_EXTI, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu6050, DEVHW_MPU6050, MPU6050_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU6500)
|
||||
#if defined(MPU6500_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU_INT_EXTI, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#elif defined(MPU6500_I2C_BUS)
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu6500, DEVHW_MPU6500, MPU6500_I2C_BUS, MPU_ADDRESS, MPU_INT_EXTI, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu6500, DEVHW_MPU6500, MPU6500_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU9250)
|
||||
#if defined(MPU9250_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, MPU_INT_EXTI, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#elif defined(MPU9250_I2C_BUS)
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu9250, DEVHW_MPU9250, MPU9250_I2C_BUS, MPU_ADDRESS, MPU_INT_EXTI, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu9250, DEVHW_MPU9250, MPU9250_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_BMI160)
|
||||
#if defined(BMI160_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_bmi160, DEVHW_BMI160, BMI160_SPI_BUS, BMI160_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#elif defined(BMI160_I2C_BUS)
|
||||
BUSDEV_REGISTER_I2C(busdev_bmi160, DEVHW_BMI160, BMI160_I2C_BUS, 0x68, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
40
src/main/target/link/stm32_flash_f446.ld
Normal file
40
src/main/target/link/stm32_flash_f446.ld
Normal file
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash_f411.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F11 Device with
|
||||
** 512KByte FLASH, 128KByte RAM
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Stack & Heap sizes */
|
||||
_Min_Heap_Size = 0;
|
||||
_Min_Stack_Size = 0x1800;
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x0807FFFF 512K full flash,
|
||||
0x08000000 to 0x08003FFF 16K isr vector, startup code,
|
||||
0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1
|
||||
0x08008000 to 0x0807FFFF 480K firmware,
|
||||
*/
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
|
||||
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash_split.ld"
|
|
@ -369,24 +369,18 @@ uint32_t hse_value = HSE_VALUE;
|
|||
/******************************************************************************/
|
||||
|
||||
/************************* PLL Parameters *************************************/
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
|
||||
#if defined(COLIBRI) || defined(KROOZX)
|
||||
#define PLL_M 16
|
||||
#elif defined(PIXRACER)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx) || defined (STM32F446xx) || defined (STM32F410xx) || defined (STM32F411xE)
|
||||
#if HSE_VALUE == 24000000
|
||||
#define PLL_M 24
|
||||
#else
|
||||
#elif HSE_VALUE == 16000000
|
||||
#define PLL_M 16
|
||||
#elif HSE_VALUE == 8000000
|
||||
#define PLL_M 8
|
||||
#else
|
||||
#error Invalid HSE_VALUE
|
||||
#endif
|
||||
#elif defined (STM32F446xx)
|
||||
#define PLL_M 8
|
||||
#elif defined (STM32F410xx) || defined (STM32F411xE)
|
||||
#if defined(USE_HSE_BYPASS)
|
||||
#define PLL_M 8
|
||||
#else /* !USE_HSE_BYPASS */
|
||||
#define PLL_M 8
|
||||
#endif /* USE_HSE_BYPASS */
|
||||
#else
|
||||
#error Undefined CPU
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
|
||||
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue