34 #define while_check(cond, result) \ 36 int32_t timeout_var = 200; \ 37 while ((cond) && timeout_var) \ 41 handle_hardware_failure();\ 42 result = RESULT_ERROR; \ 46 #define log_line event_history_.add_event(__LINE__) 146 for (
int i = 0;
i < 16; ++
i)
179 int8_t
I2C::read(uint8_t
addr, uint8_t
reg, uint8_t num_bytes, uint8_t *data,
void(*callback)(uint8_t),
bool blocking)
237 int8_t
I2C::read(uint8_t addr, uint8_t reg, uint8_t *data)
256 uint32_t timeout = 500;
280 uint32_t timeout = 500;
298 int8_t
I2C::write(uint8_t addr, uint8_t reg, uint8_t data,
void(*callback)(uint8_t),
bool blocking)
351 uint32_t timeout = 500;
499 else if (last_event ==
SB)
#define DMA_MemoryInc_Enable
void I2C_DMALastTransferCmd(I2C_TypeDef *I2Cx, FunctionalState NewState)
Specifies that the next DMA transfer is the last one.
void transfer_complete_cb()
void GPIO_PinAFConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
Changes the mapping of the specified pin.
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
#define DMA_MemoryDataSize_Byte
void I2C_ClearFlag(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG)
Clears the I2Cx's pending flags.
uint16_t I2C_AcknowledgedAddress
void I2C1_ER_IRQHandler(void)
void I2C3_EV_IRQHandler(void)
#define I2C_EVENT_MASTER_MODE_SELECT
Communication start.
void I2C_AcknowledgeConfig(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C acknowledge feature.
void set_mode(gpio_mode_t mode)
void DMA_DeInit(DMA_Stream_TypeDef *DMAy_Streamx)
Deinitialize the DMAy Streamx registers to their default reset values.
void I2C_GenerateSTART(I2C_TypeDef *I2Cx, FunctionalState NewState)
Generates I2Cx communication START condition.
void DMA1_Stream0_IRQHandler(void)
#define I2C_EVENT_MASTER_BYTE_TRANSMITTED
#define DMA_PeripheralInc_Disable
void delayMicroseconds(uint32_t us)
void I2C_Send7bitAddress(I2C_TypeDef *I2Cx, uint8_t Address, uint8_t I2C_Direction)
Transmits the address byte to select the slave device.
uint8_t I2C_ReceiveData(I2C_TypeDef *I2Cx)
Returns the most recent received data by the I2Cx peripheral.
Debug_History interrupt_history_
uint32_t DMA_MemoryDataSize
void init(const i2c_hardware_struct_t *c)
void add_event(uint32_t event)
FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_FLAG)
Checks whether the specified DMAy Streamx flag is set or not.
#define DMA_Priority_High
void DMA_Init(DMA_Stream_TypeDef *DMAy_Streamx, DMA_InitTypeDef *DMA_InitStruct)
Initializes the DMAy Streamx according to the specified parameters in the DMA_InitStruct structure...
uint8_t NVIC_IRQChannelSubPriority
void I2C_GenerateSTOP(I2C_TypeDef *I2Cx, FunctionalState NewState)
Generates I2Cx communication STOP condition.
void I2C2_EV_IRQHandler(void)
uint32_t DMA_PeripheralInc
void DMA1_Stream2_IRQHandler(void)
NVIC Init Structure definition.
DMA_InitTypeDef DMA_InitStructure_
volatile uint64_t micros(void)
volatile current_status_t current_status_
void DMA_ITConfig(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState)
Enables or disables the specified DMAy Streamx interrupts.
#define I2C_Direction_Transmitter
uint32_t DMA_PeripheralDataSize
#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED
Address Acknowledge.
#define I2C_AcknowledgedAddress_7bit
#define DMA_FIFOMode_Enable
#define DMA_FIFOThreshold_Full
void I2C_DeInit(I2C_TypeDef *I2Cx)
Deinitializes the I2Cx peripheral registers to their default reset values.
void init(GPIO_TypeDef *BasePort, uint16_t pin, gpio_mode_t mode)
void I2C2_ER_IRQHandler(void)
void I2C_StructInit(I2C_InitTypeDef *I2C_InitStruct)
Fills each I2C_InitStruct member with its default value.
uint32_t DMA_PeripheralBurst
void I2C1_EV_IRQHandler(void)
static volatile uint8_t addr
void handle_hardware_failure()
void DMA_Cmd(DMA_Stream_TypeDef *DMAy_Streamx, FunctionalState NewState)
Enables or disables the specified DMAy Streamx.
uint32_t DMA_PeripheralBaseAddr
uint32_t DMA_Memory0BaseAddr
void I2C_Cmd(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C peripheral.
static volatile uint8_t reg
#define DMA_MemoryBurst_Single
uint32_t DMA_FIFOThreshold
void I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef *I2C_InitStruct)
Initializes the I2Cx peripheral according to the specified parameters in the I2C_InitStruct.
FunctionalState NVIC_IRQChannelCmd
void write(gpio_write_t state)
uint8_t NVIC_IRQChannelPreemptionPriority
void I2C3_ER_IRQHandler(void)
#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED
I2C Init structure definition.
#define while_check(cond, result)
#define DMA_PeripheralDataSize_Byte
int8_t write(uint8_t addr, uint8_t reg, uint8_t data, void(*callback)(uint8_t), bool blocking=false)
DMA_Stream_TypeDef * DMA_Stream
volatile uint8_t return_code_
FlagStatus I2C_GetFlagStatus(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG)
Checks whether the specified I2C flag is set or not.
#define DMA_DIR_PeripheralToMemory
const i2c_hardware_struct_t * c_
int8_t read(uint8_t addr, uint8_t reg, uint8_t num_bytes, uint8_t *data, void(*callback)(uint8_t)=nullptr, bool blocking=false)
void I2C_DMACmd(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C DMA requests.
#define I2C_Direction_Receiver
uint32_t I2C_GetLastEvent(I2C_TypeDef *I2Cx)
Returns the last I2Cx Event.
void I2C_SendData(I2C_TypeDef *I2Cx, uint8_t Data)
Sends a data byte through the I2Cx peripheral.
void DMA_ClearFlag(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_FLAG)
Clears the DMAy Streamx's pending flags.
void I2C_ITConfig(I2C_TypeDef *I2Cx, uint16_t I2C_IT, FunctionalState NewState)
Enables or disables the specified I2C interrupts.
void DMA_SetCurrDataCounter(DMA_Stream_TypeDef *DMAy_Streamx, uint16_t Counter)
Writes the number of data units to be transferred on the DMAy Streamx.
ErrorStatus I2C_CheckEvent(I2C_TypeDef *I2Cx, uint32_t I2C_EVENT)
Checks whether the last I2Cx Event is equal to the one passed as parameter.
#define DMA_PeripheralBurst_Single
#define I2C_EVENT_MASTER_BYTE_RECEIVED
Communication events.