HAL_ChibiOS: support I2C devices on STM32F7 without DMA
this allows us to support I2C4 on fmuv5
This commit is contained in:
parent
2af8e673cc
commit
e068106669
@ -255,6 +255,10 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
// calculate a timeout as twice the expected transfer time, and set as min of 4ms
|
// calculate a timeout as twice the expected transfer time, and set as min of 4ms
|
||||||
uint32_t timeout_ms = 1+2*(((8*1000000UL/bus.busclock)*MAX(send_len, recv_len))/1000);
|
uint32_t timeout_ms = 1+2*(((8*1000000UL/bus.busclock)*MAX(send_len, recv_len))/1000);
|
||||||
timeout_ms = MAX(timeout_ms, _timeout_ms);
|
timeout_ms = MAX(timeout_ms, _timeout_ms);
|
||||||
|
|
||||||
|
// if we are not using DMA then we may need to start the bus here
|
||||||
|
bus.dma_allocate(bus.dma_handle);
|
||||||
|
|
||||||
bus.i2c_active = true;
|
bus.i2c_active = true;
|
||||||
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||||
if(send_len == 0) {
|
if(send_len == 0) {
|
||||||
|
@ -85,14 +85,11 @@ PF0 I2C2_SDA I2C2
|
|||||||
PH7 I2C3_SCL I2C3
|
PH7 I2C3_SCL I2C3
|
||||||
PH8 I2C3_SDA I2C3
|
PH8 I2C3_SDA I2C3
|
||||||
|
|
||||||
# I2C4 disabled due to DMA conflicts.
|
PF14 I2C4_SCK I2C4 NODMA
|
||||||
# to support I2C4 we will need to add support in ChibiOS for
|
PF15 I2C4_SDA I2C4 NODMA
|
||||||
# using DMA on some I2C devices and not on others
|
|
||||||
#PF14 I2C4_SCK I2C4
|
|
||||||
#PF15 I2C4_SDA I2C4
|
|
||||||
|
|
||||||
# order of I2C buses
|
# order of I2C buses
|
||||||
I2C_ORDER I2C2 I2C1 I2C3
|
I2C_ORDER I2C2 I2C1 I2C3 I2C4
|
||||||
|
|
||||||
|
|
||||||
# enable pins
|
# enable pins
|
||||||
|
@ -627,17 +627,22 @@ def write_I2C_config(f):
|
|||||||
for dev in i2c_list:
|
for dev in i2c_list:
|
||||||
if not dev.startswith('I2C') or dev[3] not in "1234":
|
if not dev.startswith('I2C') or dev[3] not in "1234":
|
||||||
error("Bad I2C_ORDER element %s" % dev)
|
error("Bad I2C_ORDER element %s" % dev)
|
||||||
|
n = int(dev[3:])
|
||||||
|
devlist.append('HAL_I2C%u_CONFIG' % n)
|
||||||
|
f.write('''
|
||||||
|
#if defined(STM32_I2C_I2C%u_RX_DMA_STREAM) && defined(STM32_I2C_I2C%u_TX_DMA_STREAM)
|
||||||
|
#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM }
|
||||||
|
#else
|
||||||
|
#define HAL_I2C%u_CONFIG { &I2CD%u, SHARED_DMA_NONE, SHARED_DMA_NONE }
|
||||||
|
#endif
|
||||||
|
'''
|
||||||
|
% (n, n, n, n, n, n, n, n))
|
||||||
if dev + "_SCL" in bylabel:
|
if dev + "_SCL" in bylabel:
|
||||||
p = bylabel[dev + "_SCL"]
|
p = bylabel[dev + "_SCL"]
|
||||||
f.write(
|
f.write(
|
||||||
'#define HAL_%s_SCL_AF %d\n' % (dev, p.af)
|
'#define HAL_%s_SCL_AF %d\n' % (dev, p.af)
|
||||||
)
|
)
|
||||||
n = int(dev[3:])
|
f.write('\n#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||||
devlist.append('HAL_I2C%u_CONFIG' % n)
|
|
||||||
f.write(
|
|
||||||
'#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM }\n'
|
|
||||||
% (n, n, n, n))
|
|
||||||
f.write('#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
|
||||||
|
|
||||||
def parse_timer(str):
|
def parse_timer(str):
|
||||||
'''parse timer channel string, i.e TIM8_CH2N'''
|
'''parse timer channel string, i.e TIM8_CH2N'''
|
||||||
@ -942,7 +947,6 @@ def write_hwdef_header(outfilename):
|
|||||||
|
|
||||||
write_mcu_config(f)
|
write_mcu_config(f)
|
||||||
write_USB_config(f)
|
write_USB_config(f)
|
||||||
write_I2C_config(f)
|
|
||||||
write_SPI_config(f)
|
write_SPI_config(f)
|
||||||
write_ADC_config(f)
|
write_ADC_config(f)
|
||||||
write_GPIO_config(f)
|
write_GPIO_config(f)
|
||||||
@ -957,6 +961,7 @@ def write_hwdef_header(outfilename):
|
|||||||
|
|
||||||
write_PWM_config(f)
|
write_PWM_config(f)
|
||||||
|
|
||||||
|
write_I2C_config(f)
|
||||||
write_UART_config(f)
|
write_UART_config(f)
|
||||||
|
|
||||||
if len(romfs) > 0:
|
if len(romfs) > 0:
|
||||||
@ -1033,8 +1038,15 @@ def build_peripheral_list():
|
|||||||
continue
|
continue
|
||||||
for prefix in prefixes:
|
for prefix in prefixes:
|
||||||
if type.startswith(prefix):
|
if type.startswith(prefix):
|
||||||
peripherals.append(type + "_TX")
|
ptx = type + "_TX"
|
||||||
peripherals.append(type + "_RX")
|
prx = type + "_RX"
|
||||||
|
peripherals.append(ptx)
|
||||||
|
peripherals.append(prx)
|
||||||
|
if not ptx in bylabel:
|
||||||
|
bylabel[ptx] = p
|
||||||
|
if not prx in bylabel:
|
||||||
|
bylabel[prx] = p
|
||||||
|
|
||||||
if type.startswith('ADC'):
|
if type.startswith('ADC'):
|
||||||
peripherals.append(type)
|
peripherals.append(type)
|
||||||
if type.startswith('SDIO') or type.startswith('SDMMC'):
|
if type.startswith('SDIO') or type.startswith('SDMMC'):
|
||||||
|
Loading…
Reference in New Issue
Block a user