diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk index eb329be5423..199152f8e9c 100644 --- a/make/mcu/STM32F4.mk +++ b/make/mcu/STM32F4.mk @@ -22,7 +22,8 @@ else CMSIS_DIR := $(ROOT)/lib/main/CMSIS/CM4 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) -EXCLUDES = stm32f4xx_can.c \ +EXCLUDES = stm32f4xx_crc.c \ + stm32f4xx_can.c \ stm32f4xx_fmc.c \ stm32f4xx_sai.c \ stm32f4xx_cec.c \ diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 879e4b47454..de9f754ecce 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -38,10 +38,12 @@ #include "drivers/sensor.h" #include "drivers/system.h" #include "drivers/time.h" -#include "drivers/dma_spi.h" +#ifdef USE_DMA_SPI_DEVICE +#include "drivers/dma_spi.h" #include "sensors/gyro.h" #include "sensors/acceleration.h" +#endif //USE_DMA_SPI_DEVICE #include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro_mpu3050.h" @@ -53,11 +55,17 @@ #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" +#ifdef USE_GYRO_IMUF9001 #include "drivers/accgyro/accgyro_imuf9001.h" +#endif //USE_GYRO_IMUF9001 #include "drivers/accgyro/accgyro_mpu.h" + +#ifdef USE_DMA_SPI_DEVICE volatile int dmaSpiGyroDataReady = 0; volatile uint32_t imufCrcErrorCount = 0; +#endif //USE_DMA_SPI_DEVICE + mpuResetFnPtr mpuResetFn; #ifdef USE_GYRO_IMUF9001 imufData_t imufData; diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.c b/src/main/drivers/accgyro/accgyro_mpu6500.c index e1bccd6f860..453ea1dc1e8 100644 --- a/src/main/drivers/accgyro/accgyro_mpu6500.c +++ b/src/main/drivers/accgyro/accgyro_mpu6500.c @@ -92,12 +92,7 @@ bool mpu6500GyroDetect(gyroDev_t *gyro) } gyro->initFn = mpu6500GyroInit; - - #ifdef USE_DMA_SPI_DEVICE - gyro->readFn = mpuGyroDmaSpiReadStart; - #else - gyro->readFn = mpuGyroRead; - #endif + gyro->readFn = mpuGyroRead; // 16.4 dps/lsb scalefactor gyro->scale = 1.0f / 16.4f; diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c index 64507f126db..43209c3f274 100644 --- a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c @@ -130,24 +130,15 @@ bool mpu6500SpiGyroDetect(gyroDev_t *gyro) case MPU_9250_SPI: case ICM_20608_SPI: case ICM_20602_SPI: - // 16.4 dps/lsb scalefactor - gyro->scale = 1.0f / 16.4f; - break; - case ICM_20601_SPI: - // 8.2 dps/lsb scalefactor - gyro->scale = 1.0f / 8.2f; break; default: return false; } gyro->initFn = mpu6500SpiGyroInit; - #ifdef USE_DMA_SPI_DEVICE - gyro->readFn = mpuGyroDmaSpiReadStart; - #else - gyro->readFn = mpuGyroReadSPI; - #endif - - + gyro->readFn = mpuGyroReadSPI; + // 16.4 dps/lsb scalefactor + gyro->scale = 1.0f / 16.4f; + return true; } diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index 5154f43e5c6..db98f416318 100644 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -38,7 +38,10 @@ typedef struct busDevice_s { SPI_HandleTypeDef* handle; // cached here for efficiency #endif IO_t csnPin; + +#if defined(USE_GYRO_IMUF9001) IO_t rstPin; +#endif } spi; struct deviceI2C_s { I2CDevice device; diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 0ccac8a3fc8..44acc2da2b0 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -22,9 +22,6 @@ #include #ifdef USE_SPI -#ifndef GYRO_READ_TIMEOUT - #define GYRO_READ_TIMEOUT 20 -#endif #include "drivers/bus.h" #include "drivers/bus_spi.h" @@ -32,8 +29,13 @@ #include "drivers/exti.h" #include "drivers/io.h" #include "drivers/rcc.h" +#ifdef USE_DMA_SPI_DEVICE +#ifndef GYRO_READ_TIMEOUT + #define GYRO_READ_TIMEOUT 20 +#endif //GYRO_READ_TIMEOUT #include "drivers/dma_spi.h" #include "drivers/time.h" +#endif //USE_DMA_SPI_DEVICE spiDevice_t spiDevice[SPIDEV_COUNT]; @@ -118,10 +120,10 @@ uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance) return spiDevice[device].errorCount; } -#pragma GCC push_options -#pragma GCC optimize ("O0") + bool spiBusTransfer(const busDevice_t *bus, const uint8_t *txData, uint8_t *rxData, int length) { + #ifdef USE_DMA_SPI_DEVICE (void)(bus); uint32_t timeoutCheck = millis(); @@ -146,7 +148,6 @@ bool spiBusTransfer(const busDevice_t *bus, const uint8_t *txData, uint8_t *rxDa return true; } -#pragma GCC pop_options uint16_t spiGetErrorCounter(SPI_TypeDef *instance) { diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 941d15afbb5..bae11e76e4a 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -70,7 +70,9 @@ #include "drivers/usb_io.h" #include "drivers/vtx_rtc6705.h" #include "drivers/vtx_common.h" +#ifdef USE_DMA_SPI_DEVICE #include "drivers/dma_spi.h" +#endif //USE_DMA_SPI_DEVICE #include "fc/config.h" #include "fc/fc_init.h" diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 4935a718b41..68f6917a656 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -409,7 +409,7 @@ static bool imuIsAccelerometerHealthy(void) static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs) { - static timeUs_t previousIMUUpdateTime = 0; + static timeUs_t previousIMUUpdateTime; float rawYawError = 0; bool useAcc = false; bool useMag = false; diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c index 7fe088918cc..c5ab5b3d80d 100644 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -3795,7 +3795,7 @@ static void cliImufUpdate(char *cmdline) UNUSED(cmdline); cliPrint("I muff, you muff, we all muff for IMU-F!"); cliPrintLinefeed(); - (*((uint32_t *)0x2001FFF4)) = 0xF431FA77; + (*((uint32_t *)0x2001FFEC)) = 0xF431FA77; delay(1000); cliReboot(); } @@ -3808,7 +3808,7 @@ static void cliMsd(char *cmdline) cliPrint("Loading as USB drive!"); cliPrintLinefeed(); - (*((uint32_t *)0x2001FFF8)) = 0xF431FA11; + (*((uint32_t *)0x2001FFF0)) = 0xF431FA11; delay(1000); cliReboot(); } diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index e72dc41e13f..e8cbbf7f0ea 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -51,7 +51,9 @@ #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" +#ifdef USE_GYRO_IMUF9001 #include "drivers/accgyro/accgyro_imuf9001.h" +#endif //USE_GYRO_IMUF9001 #include "drivers/bus_spi.h" #include "fc/config.h" diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index f853b6ddad5..d3f7bd5d026 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -52,7 +52,9 @@ #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" +#ifdef USE_GYRO_IMUF9001 #include "drivers/accgyro/accgyro_imuf9001.h" +#endif //USE_GYRO_IMUF9001 #include "drivers/accgyro/gyro_sync.h" #include "drivers/bus_spi.h" #include "drivers/io.h" @@ -119,20 +121,18 @@ typedef struct gyroSensor_s { biquadFilter_t notchFilterDyn[XYZ_AXIS_COUNT]; timeUs_t overflowTimeUs; bool overflowDetected; -#if defined(USE_GYRO_IMUF9001) -// do nothing -#else -#if defined(USE_GYRO_FAST_KALMAN) - // gyro kalman filter - filterApplyFnPtr fastKalmanApplyFn; - fastKalman_t fastKalman[XYZ_AXIS_COUNT]; -#endif // USE_GYRO_FAST_KALMAN -#if defined(USE_GYRO_BIQUAD_RC_FIR2) - // gyro biquad RC FIR2 filter - filterApplyFnPtr biquadRCFIR2ApplyFn; - biquadFilter_t biquadRCFIR2[XYZ_AXIS_COUNT]; -#endif // USE_GYRO_BIQUAD_RC_FIR2 -#endif //USE_GYRO_IMUF9001 +#ifndef USE_GYRO_IMUF9001 + #if defined(USE_GYRO_FAST_KALMAN) + // gyro kalman filter + filterApplyFnPtr fastKalmanApplyFn; + fastKalman_t fastKalman[XYZ_AXIS_COUNT]; + #endif // USE_GYRO_FAST_KALMAN + #if defined(USE_GYRO_BIQUAD_RC_FIR2) + // gyro biquad RC FIR2 filter + filterApplyFnPtr biquadRCFIR2ApplyFn; + biquadFilter_t biquadRCFIR2[XYZ_AXIS_COUNT]; + #endif // USE_GYRO_BIQUAD_RC_FIR2 +#endif //!USE_GYRO_IMUF9001 } gyroSensor_t; STATIC_UNIT_TESTED FAST_RAM gyroSensor_t gyroSensor1; @@ -141,16 +141,14 @@ STATIC_UNIT_TESTED gyroSensor_t * const gyroSensorPtr = &gyroSensor1; STATIC_UNIT_TESTED gyroDev_t * const gyroDevPtr = &gyroSensor1.gyroDev; #endif -#if defined(USE_GYRO_IMUF9001) -// do nothing -#else -#if defined(USE_GYRO_FAST_KALMAN) -static void gyroInitFilterKalman(gyroSensor_t *gyroSensor, uint16_t gyro_filter_q, uint16_t gyro_filter_r, uint16_t gyro_filter_p); -#endif // USE_GYRO_FAST_KALMAN -#if defined(USE_GYRO_BIQUAD_RC_FIR2) -static void gyroInitFilterBiquadRCFIR2(gyroSensor_t *gyroSensor, uint16_t lpfHz); -#endif // USE_GYRO_BIQUAD_RC_FIR2 -#endif // USE_GYRO_FAST_KALMAN +#ifndef USE_GYRO_IMUF9001 + #if defined(USE_GYRO_FAST_KALMAN) + static void gyroInitFilterKalman(gyroSensor_t *gyroSensor, uint16_t gyro_filter_q, uint16_t gyro_filter_r, uint16_t gyro_filter_p); + #endif // USE_GYRO_FAST_KALMAN + #if defined(USE_GYRO_BIQUAD_RC_FIR2) + static void gyroInitFilterBiquadRCFIR2(gyroSensor_t *gyroSensor, uint16_t lpfHz); + #endif // USE_GYRO_BIQUAD_RC_FIR2 +#endif //!USE_GYRO_IMUF9001 static void gyroInitSensorFilters(gyroSensor_t *gyroSensor); @@ -189,9 +187,9 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .imuf_mode = 32, .imuf_pitch_q = 2500, .imuf_pitch_r = 88, - .imuf_roll_q = 3500, + .imuf_roll_q = 2500, .imuf_roll_r = 88, - .imuf_yaw_q = 1500, + .imuf_yaw_q = 1250, .imuf_yaw_r = 88, .imuf_pitch_lpf_cutoff_hz = 120.0f, .imuf_roll_lpf_cutoff_hz = 120.0f, @@ -620,9 +618,7 @@ static void gyroInitFilterDynamicNotch(gyroSensor_t *gyroSensor) } #endif -#if defined(USE_GYRO_IMUF9001) -// do nothing -#else +#ifndef USE_GYRO_IMUF9001 #if defined(USE_GYRO_FAST_KALMAN) static void gyroInitFilterKalman(gyroSensor_t *gyroSensor, uint16_t gyro_filter_q, uint16_t gyro_filter_r, uint16_t gyro_filter_p) { @@ -651,23 +647,21 @@ static void gyroInitFilterBiquadRCFIR2(gyroSensor_t *gyroSensor, uint16_t lpfHz) } } #endif // USE_GYRO_BIQUAD_RC_FIR2 -#endif // USE_GYRO_IMUF9001 +#endif //!USE_GYRO_IMUF9001 static void gyroInitSensorFilters(gyroSensor_t *gyroSensor) { #if defined(USE_GYRO_SLEW_LIMITER) gyroInitSlewLimiter(gyroSensor); #endif -#if defined(USE_GYRO_IMUF9001) -// do nothing -#else -#if defined(USE_GYRO_FAST_KALMAN) - gyroInitFilterKalman(gyroSensor, gyroConfig()->gyro_filter_q, gyroConfig()->gyro_filter_r, gyroConfig()->gyro_filter_p); -#endif // USE_GYRO_FAST_KALMAN -#if defined(USE_GYRO_BIQUAD_RC_FIR2) - gyroInitFilterBiquadRCFIR2(gyroSensor, gyroConfig()->gyro_soft_lpf_hz_2); -#endif // USE_GYRO_BIQUAD_RC_FIR2 -#endif // USE_GYRO_IMUF9001 +#ifndef USE_GYRO_IMUF9001 + #if defined(USE_GYRO_FAST_KALMAN) + gyroInitFilterKalman(gyroSensor, gyroConfig()->gyro_filter_q, gyroConfig()->gyro_filter_r, gyroConfig()->gyro_filter_p); + #endif // USE_GYRO_FAST_KALMAN + #if defined(USE_GYRO_BIQUAD_RC_FIR2) + gyroInitFilterBiquadRCFIR2(gyroSensor, gyroConfig()->gyro_soft_lpf_hz_2); + #endif // USE_GYRO_BIQUAD_RC_FIR2 +#endif //!USE_GYRO_IMUF9001 #ifndef USE_GYRO_IMUF9001 gyroInitFilterLpf(gyroSensor, gyroConfig()->gyro_soft_lpf_hz); gyroInitFilterNotch1(gyroSensor, gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1); @@ -939,9 +933,7 @@ static FAST_CODE void gyroUpdateSensor(gyroSensor_t *gyroSensor, timeUs_t curren // NOTE: this branch optimized for when there is no gyro debugging, ensure it is kept in step with non-optimized branch float gyroADCf = gyroSensor->gyroDev.gyroADC[axis] * gyroSensor->gyroDev.scale; -#if defined(USE_GYRO_IMUF9001) - // do nothing -#else +#ifndef USE_GYRO_IMUF9001 #if defined(USE_GYRO_BIQUAD_RC_FIR2) #if defined(USE_GYRO_FAST_KALMAN) switch(gyroConfig()->gyro_stage2_filter_type){ @@ -958,7 +950,7 @@ static FAST_CODE void gyroUpdateSensor(gyroSensor_t *gyroSensor, timeUs_t curren break; } #endif // USE_GYRO_BIQUAD_RC_FIR2 -#endif // USE_GYRO_IMUF9001 +#endif //USE_GYRO_IMUF9001 #ifdef USE_GYRO_DATA_ANALYSE gyroADCf = gyroSensor->notchFilterDynApplyFn((filter_t *)&gyroSensor->notchFilterDyn[axis], gyroADCf); #endif diff --git a/src/main/startup/startup_stm32f40xx.s b/src/main/startup/startup_stm32f40xx.s index bc4aa97cb0c..1bb181b75c1 100644 --- a/src/main/startup/startup_stm32f40xx.s +++ b/src/main/startup/startup_stm32f40xx.s @@ -80,7 +80,7 @@ Reset_Handler: dsb // Check for imufUpdate reboot - ldr r0, =0x2001FFF4 // rs2k + ldr r0, =0x2001FFEC // rs2k ldr r1, =0xF431FA77 // rs2k ldr r2, [r0, #0] // rs2k str r0, [r0, #0] // rs2k @@ -88,7 +88,7 @@ Reset_Handler: beq rebootUpdater // rs2k // Check for msd reboot - ldr r0, =0x2001FFF8 // rs2k + ldr r0, =0x2001FFF0 // rs2k ldr r1, =0xF431FA11 // rs2k ldr r2, [r0, #0] // rs2k str r0, [r0, #0] // rs2k diff --git a/src/main/target/HELIOSPRING/config.c b/src/main/target/HELIOSPRING/config.c index c0d8a353fe7..c241b21cc9b 100644 --- a/src/main/target/HELIOSPRING/config.c +++ b/src/main/target/HELIOSPRING/config.c @@ -54,7 +54,7 @@ void targetConfiguration(void) { // pidProfile->dterm_lpf_hz = 0; // pidProfile->dterm_notch_hz = 0; // pidProfile->dterm_notch_cutoff = 0; - pidProfile->dterm_filter_type = FILTER_BIQUAD; + pidProfile->dterm_filter_type = FILTER_PT1; } } diff --git a/src/main/target/HELIOSPRING/target.h b/src/main/target/HELIOSPRING/target.h index 67ba24f5bda..e4c5bbc2c9d 100644 --- a/src/main/target/HELIOSPRING/target.h +++ b/src/main/target/HELIOSPRING/target.h @@ -182,7 +182,7 @@ #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC #define CURRENT_METER_ADC_PIN PA1 #define VBAT_ADC_PIN PA0 -#define CURRENT_METER_SCALE_DEFAULT 16000 +#define CURRENT_METER_SCALE_DEFAULT 400 #define VBAT_SCALE 109 #define CAMERA_CONTROL_PIN PB6 // define dedicated camera_osd_control pin \ No newline at end of file diff --git a/src/main/target/HELIOSPRING/target.mk b/src/main/target/HELIOSPRING/target.mk index 5a140d5ab77..ced109e6f31 100644 --- a/src/main/target/HELIOSPRING/target.mk +++ b/src/main/target/HELIOSPRING/target.mk @@ -2,7 +2,7 @@ F405_TARGETS += $(TARGET) FEATURES += VCP ONBOARDFLASH -TARGET_SRC = \ - drivers/dma_spi.c \ - drivers/accgyro/accgyro_imuf9001.c \ - drivers/max7456.c \ No newline at end of file +TARGET_SRC = stm32f4xx_crc.c \ + drivers/dma_spi.c \ + drivers/accgyro/accgyro_imuf9001.c \ + drivers/max7456.c \ No newline at end of file