mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed H7 I2C timing
we were running the clock at too low speed. This affected the SSD1306 display # Conflicts: # libraries/AP_HAL_ChibiOS/I2CDevice.cpp
This commit is contained in:
parent
abe1a09c7a
commit
8311a5be63
|
@ -54,6 +54,9 @@ I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(I2CD)];
|
|||
#define HAL_I2C_F7_100_TIMINGR 0x20404768
|
||||
#define HAL_I2C_F7_400_TIMINGR 0x6000030D
|
||||
|
||||
#define HAL_I2C_H7_100_TIMINGR 0x00707CBB
|
||||
#define HAL_I2C_H7_400_TIMINGR 0x00300F38
|
||||
|
||||
/*
|
||||
enable clear (toggling SCL) on I2C bus timeouts which leave SDA stuck low
|
||||
*/
|
||||
|
@ -123,7 +126,7 @@ I2CDeviceManager::I2CDeviceManager(void)
|
|||
drop the speed to be the minimum speed requested
|
||||
*/
|
||||
businfo[i].busclock = HAL_I2C_MAX_CLOCK;
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F7)
|
||||
if (businfo[i].busclock <= 100000) {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR;
|
||||
businfo[i].busclock = 100000;
|
||||
|
@ -131,7 +134,15 @@ I2CDeviceManager::I2CDeviceManager(void)
|
|||
businfo[i].i2ccfg.timingr = HAL_I2C_F7_400_TIMINGR;
|
||||
businfo[i].busclock = 400000;
|
||||
}
|
||||
#else
|
||||
#elif defined(STM32H7)
|
||||
if (businfo[i].busclock <= 100000) {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_H7_100_TIMINGR;
|
||||
businfo[i].busclock = 100000;
|
||||
} else {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_H7_400_TIMINGR;
|
||||
businfo[i].busclock = 400000;
|
||||
}
|
||||
#else // F1 or F4
|
||||
businfo[i].i2ccfg.op_mode = OPMODE_I2C;
|
||||
businfo[i].i2ccfg.clock_speed = businfo[i].busclock;
|
||||
if (businfo[i].i2ccfg.clock_speed <= 100000) {
|
||||
|
|
Loading…
Reference in New Issue