mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
reformat I2C driver and align comments. add timeout checking and move hardware reinit common code into separate function.
moved nvic priority group init into drv_system, where it belongs Conflicts: src/drivers/system_common.c src/drv_i2c.c
This commit is contained in:
parent
31297de7fa
commit
0e80dbf025
2 changed files with 134 additions and 136 deletions
|
@ -55,35 +55,12 @@ static volatile uint8_t reading;
|
||||||
static volatile uint8_t* write_p;
|
static volatile uint8_t* write_p;
|
||||||
static volatile uint8_t* read_p;
|
static volatile uint8_t* read_p;
|
||||||
|
|
||||||
static void i2c_er_handler(void)
|
static bool i2cHandleHardwareFailure(void)
|
||||||
{
|
{
|
||||||
volatile uint32_t SR1Register;
|
i2cErrorCount++;
|
||||||
// Read the I2C1 status register
|
// reinit peripheral + clock out garbage
|
||||||
SR1Register = I2Cx->SR1;
|
i2cInit(I2Cx);
|
||||||
if (SR1Register & 0x0F00) {
|
return false;
|
||||||
error = true;
|
|
||||||
// I2C1error.error = ((SR1Register & 0x0F00) >> 8); // save error
|
|
||||||
// I2C1error.job = job; // the task
|
|
||||||
}
|
|
||||||
|
|
||||||
// If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
|
|
||||||
if (SR1Register & 0x0700) {
|
|
||||||
(void) I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
|
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
|
|
||||||
if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop
|
|
||||||
if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start,stop will hang the peripheral
|
|
||||||
while (I2Cx->CR1 & 0x0100); // wait for any start to finish sending
|
|
||||||
I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
|
|
||||||
while (I2Cx->CR1 & 0x0200); // wait for stop to finish sending
|
|
||||||
i2cInit(I2Cx); // reset and configure the hardware
|
|
||||||
} else {
|
|
||||||
I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
|
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
|
|
||||||
busy = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||||
|
@ -102,19 +79,18 @@ bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||||
|
|
||||||
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
|
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
|
||||||
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
|
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
|
||||||
while (I2Cx->CR1 & 0x0200); // wait for any stop to finish sending
|
while (I2Cx->CR1 & 0x0200 && --timeout > 0) { ; } // wait for any stop to finish sending
|
||||||
|
if (timeout == 0)
|
||||||
|
return i2cHandleHardwareFailure();
|
||||||
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
|
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
|
||||||
}
|
}
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
|
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
|
||||||
}
|
}
|
||||||
|
|
||||||
while (busy && --timeout > 0);
|
timeout = I2C_DEFAULT_TIMEOUT;
|
||||||
if (timeout == 0) {
|
while (busy && --timeout > 0) { ; }
|
||||||
i2cErrorCount++;
|
if (timeout == 0)
|
||||||
// reinit peripheral + clock out garbage
|
return i2cHandleHardwareFailure();
|
||||||
i2cInit(I2Cx);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
return !error;
|
return !error;
|
||||||
}
|
}
|
||||||
|
@ -140,27 +116,54 @@ bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
|
||||||
|
|
||||||
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
|
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
|
||||||
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
|
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
|
||||||
while (I2Cx->CR1 & 0x0200); // wait for any stop to finish sending
|
while (I2Cx->CR1 & 0x0200 && --timeout > 0) { ; } // wait for any stop to finish sending
|
||||||
|
if (timeout == 0)
|
||||||
|
return i2cHandleHardwareFailure();
|
||||||
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
|
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
|
||||||
}
|
}
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
|
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
|
||||||
}
|
}
|
||||||
|
|
||||||
while (busy && --timeout > 0);
|
timeout = I2C_DEFAULT_TIMEOUT;
|
||||||
if (timeout == 0) {
|
while (busy && --timeout > 0) { ; }
|
||||||
i2cErrorCount++;
|
if (timeout == 0)
|
||||||
// reinit peripheral + clock out garbage
|
return i2cHandleHardwareFailure();
|
||||||
i2cInit(I2Cx);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
return !error;
|
return !error;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void i2c_er_handler(void)
|
||||||
|
{
|
||||||
|
// Read the I2C1 status register
|
||||||
|
volatile uint32_t SR1Register = I2Cx->SR1;
|
||||||
|
|
||||||
|
if (SR1Register & 0x0F00) // an error
|
||||||
|
error = true;
|
||||||
|
|
||||||
|
// If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
|
||||||
|
if (SR1Register & 0x0700) {
|
||||||
|
(void)I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
|
||||||
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
|
||||||
|
if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop
|
||||||
|
if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
|
||||||
|
while (I2Cx->CR1 & 0x0100) { ; } // wait for any start to finish sending
|
||||||
|
I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
|
||||||
|
while (I2Cx->CR1 & 0x0200) { ; } // wait for stop to finish sending
|
||||||
|
i2cInit(I2Cx); // reset and configure the hardware
|
||||||
|
} else {
|
||||||
|
I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
|
||||||
|
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
|
||||||
|
busy = 0;
|
||||||
|
}
|
||||||
|
|
||||||
void i2c_ev_handler(void)
|
void i2c_ev_handler(void)
|
||||||
{
|
{
|
||||||
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
|
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
|
||||||
static int8_t index; // index is signed -1==send the subaddress
|
static int8_t index; // index is signed -1 == send the subaddress
|
||||||
uint8_t SReg_1 = I2Cx->SR1; // read the status register here
|
uint8_t SReg_1 = I2Cx->SR1; // read the status register here
|
||||||
|
|
||||||
if (SReg_1 & 0x0001) { // we just sent a start - EV5 in ref manual
|
if (SReg_1 & 0x0001) { // we just sent a start - EV5 in ref manual
|
||||||
|
@ -183,20 +186,19 @@ void i2c_ev_handler(void)
|
||||||
if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
|
if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
|
||||||
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
||||||
__DMB();
|
__DMB();
|
||||||
(void) I2Cx->SR2; // clear ADDR after ACK is turned off
|
(void)I2Cx->SR2; // clear ADDR after ACK is turned off
|
||||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
|
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
|
||||||
final_stop = 1;
|
final_stop = 1;
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
|
||||||
} else { // EV6 and EV6_1
|
} else { // EV6 and EV6_1
|
||||||
(void) I2Cx->SR2; // clear the ADDR here
|
(void)I2Cx->SR2; // clear the ADDR here
|
||||||
__DMB();
|
__DMB();
|
||||||
if (bytes == 2 && reading && subaddress_sent) { // rx 2 bytes - EV6_1
|
if (bytes == 2 && reading && subaddress_sent) { // rx 2 bytes - EV6_1
|
||||||
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill
|
||||||
} else if (bytes == 3 && reading && subaddress_sent) // rx 3 bytes
|
} else if (bytes == 3 && reading && subaddress_sent) // rx 3 bytes
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time
|
||||||
else
|
else // receiving greater than three bytes, sending subaddress, or transmitting
|
||||||
//receiving greater than three bytes, sending subaddress, or transmitting
|
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE);
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE);
|
||||||
}
|
}
|
||||||
} else if (SReg_1 & 0x004) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
|
} else if (SReg_1 & 0x004) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
|
||||||
|
@ -206,18 +208,16 @@ void i2c_ev_handler(void)
|
||||||
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
||||||
read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
|
read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
|
||||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
||||||
final_stop = 1; // reuired to fix hardware
|
final_stop = 1; // required to fix hardware
|
||||||
read_p[index++] = (uint8_t)I2Cx->DR; // read data N-1
|
read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7
|
||||||
} else { // EV7_3
|
} else { // EV7_3
|
||||||
if (final_stop)
|
if (final_stop)
|
||||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
||||||
else
|
else
|
||||||
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
|
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
|
||||||
read_p[index++] = (uint8_t)I2Cx->DR; // read data N-1
|
read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
|
||||||
read_p[index++] = (uint8_t)I2Cx->DR; // read data N
|
read_p[index++] = (uint8_t)I2Cx->DR; // read data N
|
||||||
read_p[index++] = I2C_ReceiveData(I2Cx); // read data N-1
|
|
||||||
read_p[index++] = I2C_ReceiveData(I2Cx); // read data N
|
|
||||||
index++; // to show job completed
|
index++; // to show job completed
|
||||||
}
|
}
|
||||||
} else { // EV8_2, which may be due to a subaddress sent or a write completion
|
} else { // EV8_2, which may be due to a subaddress sent or a write completion
|
||||||
|
@ -232,41 +232,38 @@ void i2c_ev_handler(void)
|
||||||
subaddress_sent = 1; // this is set back to zero upon completion of the current task
|
subaddress_sent = 1; // this is set back to zero upon completion of the current task
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
//we must wait for the start to clear, otherwise we get constant BTF
|
// we must wait for the start to clear, otherwise we get constant BTF
|
||||||
while (I2Cx->CR1 & 0x0100);
|
while (I2Cx->CR1 & 0x0100) { ; }
|
||||||
} else if (SReg_1 & 0x0040) { //Byte received - EV7
|
} else if (SReg_1 & 0x0040) { // Byte received - EV7
|
||||||
read_p[index++] = (uint8_t)I2Cx->DR;
|
read_p[index++] = (uint8_t)I2Cx->DR;
|
||||||
if (bytes == (index + 3))
|
if (bytes == (index + 3))
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2
|
||||||
if (bytes == index) //We have completed a final EV7
|
if (bytes == index) // We have completed a final EV7
|
||||||
index++; //to show job is complete
|
index++; // to show job is complete
|
||||||
} else if (SReg_1 & 0x0080) { //Byte transmitted -EV8/EV8_1
|
} else if (SReg_1 & 0x0080) { // Byte transmitted EV8 / EV8_1
|
||||||
if (index != -1) { //we dont have a subaddress to send
|
if (index != -1) { // we dont have a subaddress to send
|
||||||
I2Cx->DR = write_p[index++];
|
I2Cx->DR = write_p[index++];
|
||||||
if (bytes == index) //we have sent all the data
|
if (bytes == index) // we have sent all the data
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
|
||||||
} else {
|
} else {
|
||||||
index++;
|
index++;
|
||||||
I2Cx->DR = reg; // send the subaddress
|
I2Cx->DR = reg; // send the subaddress
|
||||||
if (reading || !bytes) //if receiving or sending 0 bytes, flush now
|
if (reading || !bytes) // if receiving or sending 0 bytes, flush now
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush
|
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (index == bytes + 1) { //we have completed the current job
|
if (index == bytes + 1) { // we have completed the current job
|
||||||
//Completion Tasks go here
|
subaddress_sent = 0; // reset this here
|
||||||
//End of completion tasks
|
if (final_stop) // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
|
||||||
subaddress_sent = 0; //reset this here
|
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
|
||||||
// I2Cx->CR1 &= ~0x0800; //reset the POS bit so NACK applied to the current byte
|
|
||||||
if (final_stop) //If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
|
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Disable EVT and ERR interrupts while bus inactive
|
|
||||||
busy = 0;
|
busy = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void i2cInit(I2C_TypeDef *I2C)
|
void i2cInit(I2C_TypeDef *I2C)
|
||||||
{
|
{
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
NVIC_InitTypeDef nvic;
|
||||||
I2C_InitTypeDef I2C_InitStructure;
|
I2C_InitTypeDef i2c;
|
||||||
gpio_config_t gpio;
|
gpio_config_t gpio;
|
||||||
|
|
||||||
// Init pins
|
// Init pins
|
||||||
|
@ -282,29 +279,27 @@ void i2cInit(I2C_TypeDef *I2C)
|
||||||
|
|
||||||
// Init I2C
|
// Init I2C
|
||||||
I2C_DeInit(I2Cx);
|
I2C_DeInit(I2Cx);
|
||||||
I2C_StructInit(&I2C_InitStructure);
|
I2C_StructInit(&i2c);
|
||||||
|
|
||||||
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Enable EVT and ERR interrupts - they are enabled by the first request
|
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Enable EVT and ERR interrupts - they are enabled by the first request
|
||||||
I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
i2c.I2C_Mode = I2C_Mode_I2C;
|
||||||
I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
|
i2c.I2C_DutyCycle = I2C_DutyCycle_2;
|
||||||
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
i2c.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||||
I2C_InitStructure.I2C_ClockSpeed = 400000;
|
i2c.I2C_ClockSpeed = 400000;
|
||||||
I2C_Cmd(I2Cx, ENABLE);
|
I2C_Cmd(I2Cx, ENABLE);
|
||||||
I2C_Init(I2Cx, &I2C_InitStructure);
|
I2C_Init(I2Cx, &i2c);
|
||||||
|
|
||||||
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
|
|
||||||
|
|
||||||
// I2C ER Interrupt
|
// I2C ER Interrupt
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = I2C2_ER_IRQn;
|
nvic.NVIC_IRQChannel = I2C2_ER_IRQn;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
nvic.NVIC_IRQChannelPreemptionPriority = 0;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
nvic.NVIC_IRQChannelSubPriority = 0;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
nvic.NVIC_IRQChannelCmd = ENABLE;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&nvic);
|
||||||
|
|
||||||
// I2C EV Interrupt
|
// I2C EV Interrupt
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQn;
|
nvic.NVIC_IRQChannel = I2C2_EV_IRQn;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
nvic.NVIC_IRQChannelPreemptionPriority = 0;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&nvic);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t i2cGetErrorCounter(void)
|
uint16_t i2cGetErrorCounter(void)
|
||||||
|
|
|
@ -102,6 +102,9 @@ void systemInit(bool overclock)
|
||||||
SetSysClock(overclock);
|
SetSysClock(overclock);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Configure NVIC preempt/priority groups
|
||||||
|
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
|
||||||
|
|
||||||
// Turn on clocks for stuff we use
|
// Turn on clocks for stuff we use
|
||||||
#ifdef STM32F10X_MD
|
#ifdef STM32F10X_MD
|
||||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue