diff --git a/src/main/config/config.c b/src/main/config/config.c index 289f2e571d..84bbaf4de2 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -128,7 +128,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 108; +static const uint8_t EEPROM_CONF_VERSION = 109; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -453,6 +453,7 @@ static void resetConf(void) resetSerialConfig(&masterConfig.serialConfig); masterConfig.emf_avoidance = 0; + masterConfig.i2c_overclock = 0; resetPidProfile(¤tProfile->pidProfile); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 723af0ccf8..d14345dc8e 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -26,6 +26,7 @@ typedef struct master_t { uint8_t mixerMode; uint32_t enabledFeatures; uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band + uint8_t i2c_overclock; // i2c clockspeed, 0 = 400kHz default (conform specs), 1 = 800kHz, 2 = 1200kHz motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS]; #ifdef USE_SERVOS diff --git a/src/main/drivers/accgyro_mpu6050.c b/src/main/drivers/accgyro_mpu6050.c index bcb876de38..6e9d1b3b69 100644 --- a/src/main/drivers/accgyro_mpu6050.c +++ b/src/main/drivers/accgyro_mpu6050.c @@ -434,10 +434,8 @@ static void mpu6050GyroInit(void) // Accel scale 8g (4096 LSB/g) ack = i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3); -// ack = i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_PIN_CFG, -// 0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS ack = i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_PIN_CFG, - 0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS + 0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS #ifdef USE_MPU_DATA_READY_SIGNAL ack = i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN); diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h index 39db2094ec..6bcaac1103 100644 --- a/src/main/drivers/bus_i2c.h +++ b/src/main/drivers/bus_i2c.h @@ -23,6 +23,7 @@ typedef enum I2CDevice { I2CDEV_MAX = I2CDEV_2, } I2CDevice; +void i2cSetClockSelect(uint8_t clockSelect); void i2cInit(I2CDevice index); bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data); bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data); diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 026dccf507..34ef22ad62 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -61,6 +61,7 @@ static const i2cDevice_t i2cHardwareMap[] = { static I2C_TypeDef *I2Cx = NULL; // Copy of device index for reinit, etc purposes static I2CDevice I2Cx_index; +static uint8_t i2cClockSelect = 0; void I2C1_ER_IRQHandler(void) { @@ -312,6 +313,11 @@ void i2c_ev_handler(void) } } +void i2cSetClockSelect(uint8_t clockSelect) +{ + i2cClockSelect = clockSelect; +} + void i2cInit(I2CDevice index) { NVIC_InitTypeDef nvic; @@ -340,7 +346,24 @@ void i2cInit(I2CDevice index) i2c.I2C_Mode = I2C_Mode_I2C; i2c.I2C_DutyCycle = I2C_DutyCycle_2; i2c.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; - i2c.I2C_ClockSpeed = 400000; + // Overclocking i2c, test results + // Default speed, conform specs is 400000 (400 kHz) + // 2.0* : 800kHz - worked without errors + // 3.0* : 1200kHz - worked without errors + // 3.5* : 1400kHz - failed, hangup, bootpin recovery needed + // 4.0* : 1600kHz - failed, hangup, bootpin recovery needed + switch (i2cClockSelect) { + default: + case 0: + i2c.I2C_ClockSpeed = 400000; + break; + case 1: + i2c.I2C_ClockSpeed = 800000; + break; + case 2: + i2c.I2C_ClockSpeed = 1200000; + break; + } I2C_Cmd(I2Cx, ENABLE); I2C_Init(I2Cx, &i2c); diff --git a/src/main/drivers/compass_ak8975.c b/src/main/drivers/compass_ak8975.c index 365e24968f..57260d86cb 100644 --- a/src/main/drivers/compass_ak8975.c +++ b/src/main/drivers/compass_ak8975.c @@ -129,7 +129,7 @@ bool ak8975Read(int16_t *magData) for (uint8_t i = 0; i < 6; i++) { ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL + i, 1, &buf[i]); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH if (!ack) { - break false + return false } } #endif diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index a59186d51f..6911034a7d 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -310,7 +310,7 @@ bool hmc5883lRead(int16_t *magData) uint8_t buf[6]; bool ack = i2cRead(MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); - if (ack) { + if (!ack) { return false; } // During calibration, magGain is 1.0, so the read returns normal non-calibrated values. diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 67ea4a3f4a..e6b62d7305 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -52,4 +52,3 @@ typedef enum { FAILURE_FLASH_WRITE_FAILED } failureMode_e; -#define FAILURE_MODE_COUNT 4 diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index f2bd18fc66..e433999b93 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -48,6 +48,7 @@ #include "config/runtime_config.h" //#define DEBUG_IMU +#define DEBUG_IMU_SPEED int16_t accSmooth[XYZ_AXIS_COUNT]; int32_t accSum[XYZ_AXIS_COUNT]; @@ -182,10 +183,17 @@ int16_t imuCalculateHeading(t_fp_vector *vec) return head; } +#if 0 void imuUpdate(rollAndPitchTrims_t *accelerometerTrims) { +#ifdef DEBUG_IMU_SPEED + uint32_t time = micros(); +#endif gyroUpdate(); - +#ifdef DEBUG_IMU_SPEED + debug[0] = micros() - time; + time = micros(); +#endif if (sensors(SENSOR_ACC)) { qAccProcessingStateMachine(accelerometerTrims); } else { @@ -193,8 +201,37 @@ void imuUpdate(rollAndPitchTrims_t *accelerometerTrims) accADC[Y] = 0; accADC[Z] = 0; } +#ifdef DEBUG_IMU_SPEED + debug[2] = debug[0] + debug[1]; +#endif } +#else + +void imuUpdate(rollAndPitchTrims_t *accelerometerTrims) +{ +#ifdef DEBUG_IMU_SPEED + uint32_t time = micros(); +#endif + gyroUpdate(); +#ifdef DEBUG_IMU_SPEED + debug[0] = micros() - time; + time = micros(); +#endif + if (sensors(SENSOR_ACC)) { + qAccProcessingStateMachine(accelerometerTrims); + } else { + accADC[X] = 0; + accADC[Y] = 0; + accADC[Z] = 0; + } +#ifdef DEBUG_IMU_SPEED + debug[2] = debug[0] + debug[1]; +#endif +} + +#endif + int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value) { float cosZ = EstG.V.Z / sqrtf(EstG.V.X * EstG.V.X + EstG.V.Y * EstG.V.Y + EstG.V.Z * EstG.V.Z); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 8452e3eb6a..d1023872c9 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -325,6 +325,7 @@ typedef struct { const clivalue_t valueTable[] = { { "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 }, + { "i2c_overclock", VAR_UINT8 | MASTER_VALUE, &masterConfig.i2c_overclock, 0, 2 }, { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, 1200, 1700 }, { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX }, diff --git a/src/main/main.c b/src/main/main.c index 95b6f63988..e563cd29e6 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -168,6 +168,7 @@ void init(void) // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers // Configure the Flash Latency cycles and enable prefetch buffer SetSysClock(masterConfig.emf_avoidance); + i2cSetClockSelect(masterConfig.i2c_overclock); #endif #ifdef USE_HARDWARE_REVISION_DETECTION diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 17d58e8667..0c3b70c742 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -19,11 +19,13 @@ #include #include "platform.h" +#include "debug.h" #include "common/axis.h" #include "drivers/sensor.h" #include "drivers/accgyro.h" +#include "drivers/system.h" #include "sensors/battery.h" #include "sensors/sensors.h" @@ -34,6 +36,8 @@ #include "sensors/acceleration.h" +#define DEBUG_IMU_SPEED + int16_t accADC[XYZ_AXIS_COUNT]; acc_t acc; // acc access functions @@ -171,9 +175,15 @@ void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims) void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims) { +#ifdef DEBUG_IMU_SPEED + uint32_t time = micros(); +#endif if (!acc.read(accADC)) { return; } +#ifdef DEBUG_IMU_SPEED + debug[1] = micros() - time; +#endif alignSensors(accADC, accADC, accAlign); if (!isAccelerationCalibrationComplete()) {