1
0
forked from me/IronOS

Run formatter

This commit is contained in:
Ben V. Brown
2021-02-24 20:30:36 +11:00
parent 2f73c99fa4
commit 3e56826e04
10 changed files with 1688 additions and 1715 deletions

View File

@@ -9,123 +9,114 @@
#include "main.hpp"
#include <IRQ.h>
const uint16_t powerPWM = 255;
const uint8_t holdoffTicks = 25; // delay of 7 ms
const uint8_t tempMeasureTicks = 25;
const uint16_t powerPWM = 255;
const uint8_t holdoffTicks = 25; // delay of 7 ms
const uint8_t tempMeasureTicks = 25;
uint16_t totalPWM; // htim2.Init.Period, the full PWM cycle
// 2 second filter (ADC is PID_TIM_HZ Hz)
history<uint16_t, PID_TIM_HZ> rawTempFilter = { { 0 }, 0, 0 };
void resetWatchdog() {
fwdgt_counter_reload();
}
history<uint16_t, PID_TIM_HZ> rawTempFilter = {{0}, 0, 0};
void resetWatchdog() { fwdgt_counter_reload(); }
uint16_t getTipInstantTemperature() {
volatile uint16_t sum = 0; // 12 bit readings * 8*2 -> 16 bits
volatile uint16_t sum = 0; // 12 bit readings * 8*2 -> 16 bits
for (int i = 0; i < 4; i++) {
sum += adc_inserted_data_read(ADC0, i);
sum += adc_inserted_data_read(ADC1, i);
}
return sum; // 8x over sample
for (int i = 0; i < 4; i++) {
sum += adc_inserted_data_read(ADC0, i);
sum += adc_inserted_data_read(ADC1, i);
}
return sum; // 8x over sample
}
uint16_t getTipRawTemp(uint8_t refresh) {
if (refresh) {
uint16_t lastSample = getTipInstantTemperature();
rawTempFilter.update(lastSample);
return lastSample;
} else {
return rawTempFilter.average();
}
if (refresh) {
uint16_t lastSample = getTipInstantTemperature();
rawTempFilter.update(lastSample);
return lastSample;
} else {
return rawTempFilter.average();
}
}
uint16_t getHandleTemperature() {
#ifdef TEMP_TMP36
// We return the current handle temperature in X10 C
// TMP36 in handle, 0.5V offset and then 10mV per deg C (0.75V @ 25C for
// example) STM32 = 4096 count @ 3.3V input -> But We oversample by 32/(2^2) =
// 8 times oversampling Therefore 32768 is the 3.3V input, so 0.1007080078125
// mV per count So we need to subtract an offset of 0.5V to center on 0C
// (4964.8 counts)
//
int32_t result = getADC(0);
result -= 4965; // remove 0.5V offset
// 10mV per C
// 99.29 counts per Deg C above 0C
result *= 100;
result /= 993;
return result;
// We return the current handle temperature in X10 C
// TMP36 in handle, 0.5V offset and then 10mV per deg C (0.75V @ 25C for
// example) STM32 = 4096 count @ 3.3V input -> But We oversample by 32/(2^2) =
// 8 times oversampling Therefore 32768 is the 3.3V input, so 0.1007080078125
// mV per count So we need to subtract an offset of 0.5V to center on 0C
// (4964.8 counts)
//
int32_t result = getADC(0);
result -= 4965; // remove 0.5V offset
// 10mV per C
// 99.29 counts per Deg C above 0C
result *= 100;
result /= 993;
return result;
#else
#error
#endif
}
uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample) {
static uint8_t preFillneeded = 10;
static uint32_t samples[BATTFILTERDEPTH];
static uint8_t index = 0;
if (preFillneeded) {
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
samples[i] = getADC(1);
preFillneeded--;
}
if (sample) {
samples[index] = getADC(1);
index = (index + 1) % BATTFILTERDEPTH;
}
uint32_t sum = 0;
static uint8_t preFillneeded = 10;
static uint32_t samples[BATTFILTERDEPTH];
static uint8_t index = 0;
if (preFillneeded) {
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
samples[i] = getADC(1);
preFillneeded--;
}
if (sample) {
samples[index] = getADC(1);
index = (index + 1) % BATTFILTERDEPTH;
}
uint32_t sum = 0;
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
sum += samples[i];
for (uint8_t i = 0; i < BATTFILTERDEPTH; i++)
sum += samples[i];
sum /= BATTFILTERDEPTH;
if (divisor == 0) {
divisor = 1;
}
return sum * 4 / divisor;
sum /= BATTFILTERDEPTH;
if (divisor == 0) {
divisor = 1;
}
return sum * 4 / divisor;
}
void unstick_I2C() {
/* configure SDA/SCL for GPIO */
GPIO_BC(GPIOB) |= SDA_Pin | SCL_Pin;
gpio_init(SDA_GPIO_Port, GPIO_MODE_OUT_OD, GPIO_OSPEED_50MHZ, SDA_Pin | SCL_Pin);
for (int i = 0; i < 8; i++) {
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
GPIO_BOP(GPIOB) |= SCL_Pin;
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
GPIO_BOP(GPIOB) &= SCL_Pin;
}
/* connect PB6 to I2C0_SCL */
/* connect PB7 to I2C0_SDA */
gpio_init(SDA_GPIO_Port, GPIO_MODE_AF_OD, GPIO_OSPEED_50MHZ, SDA_Pin | SCL_Pin);
/* configure SDA/SCL for GPIO */
GPIO_BC(GPIOB) |= SDA_Pin | SCL_Pin;
gpio_init(SDA_GPIO_Port, GPIO_MODE_OUT_OD, GPIO_OSPEED_50MHZ, SDA_Pin | SCL_Pin);
for (int i = 0; i < 8; i++) {
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
GPIO_BOP(GPIOB) |= SCL_Pin;
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
GPIO_BOP(GPIOB) &= SCL_Pin;
}
/* connect PB6 to I2C0_SCL */
/* connect PB7 to I2C0_SDA */
gpio_init(SDA_GPIO_Port, GPIO_MODE_AF_OD, GPIO_OSPEED_50MHZ, SDA_Pin | SCL_Pin);
}
uint8_t getButtonA() {
return (gpio_input_bit_get(KEY_A_GPIO_Port, KEY_A_Pin) == SET) ? 1 : 0;
}
uint8_t getButtonB() {
return (gpio_input_bit_get(KEY_B_GPIO_Port, KEY_B_Pin) == SET) ? 1 : 0;
}
uint8_t getButtonA() { return (gpio_input_bit_get(KEY_A_GPIO_Port, KEY_A_Pin) == SET) ? 1 : 0; }
uint8_t getButtonB() { return (gpio_input_bit_get(KEY_B_GPIO_Port, KEY_B_Pin) == SET) ? 1 : 0; }
void reboot() {
// Spin for watchdog
for (;;) {
}
// Spin for watchdog
for (;;) {}
}
void delay_ms(uint16_t count) {
delay_1ms(count);
}
void delay_ms(uint16_t count) { delay_1ms(count); }
uint32_t __get_IPSR(void) {
return 0; // To shut-up CMSIS
return 0; // To shut-up CMSIS
}

View File

@@ -9,39 +9,39 @@
extern "C" {
#include "gd32vf103_usart.h"
}
char uartOutputBuffer[uartOutputBufferLength];
volatile uint32_t currentOutputPos = 0xFF;
volatile uint32_t outputLength = 0;
char uartOutputBuffer[uartOutputBufferLength];
volatile uint32_t currentOutputPos = 0xFF;
volatile uint32_t outputLength = 0;
extern volatile uint8_t pendingPWM;
void log_system_state(int32_t PWMWattsx10) {
if (currentOutputPos == 0xFF) {
void log_system_state(int32_t PWMWattsx10) {
if (currentOutputPos == 0xFF) {
// Want to print a CSV log out the uart
// Tip_Temp_C,Handle_Temp_C,Output_Power_Wattx10,PWM,Tip_Raw\r\n
// 3+1+3+1+3+1+3+1+5+2 = 23, so sizing at 32 for now
// Want to print a CSV log out the uart
// Tip_Temp_C,Handle_Temp_C,Output_Power_Wattx10,PWM,Tip_Raw\r\n
// 3+1+3+1+3+1+3+1+5+2 = 23, so sizing at 32 for now
outputLength = snprintf(uartOutputBuffer, uartOutputBufferLength, "%lu,%u,%li,%u,%lu\r\n", //
TipThermoModel::getTipInC(false), // Tip temp in C
getHandleTemperature(), // Handle temp in C X10
PWMWattsx10, // Output Wattage
pendingPWM, // PWM
TipThermoModel::convertTipRawADCTouV(getTipRawTemp(0), true) // Tip temp in uV
);
outputLength = snprintf(uartOutputBuffer, uartOutputBufferLength, "%lu,%u,%li,%u,%lu\r\n", //
TipThermoModel::getTipInC(false), // Tip temp in C
getHandleTemperature(), // Handle temp in C X10
PWMWattsx10, // Output Wattage
pendingPWM, // PWM
TipThermoModel::convertTipRawADCTouV(getTipRawTemp(0), true) // Tip temp in uV
);
// Now print this out the uart via IRQ (DMA cant be used as oled has it)
currentOutputPos = 0;
/* enable USART1 Transmit Buffer Empty interrupt */
usart_interrupt_enable(UART_PERIF, USART_INT_TBE);
}
// Now print this out the uart via IRQ (DMA cant be used as oled has it)
currentOutputPos = 0;
/* enable USART1 Transmit Buffer Empty interrupt */
usart_interrupt_enable(UART_PERIF, USART_INT_TBE);
}
}
void USART1_IRQHandler(void) {
if (RESET != usart_interrupt_flag_get(UART_PERIF, USART_INT_FLAG_TBE)) {
/* write one byte to the transmit data register */
usart_data_transmit(UART_PERIF, uartOutputBuffer[currentOutputPos++]);
if (currentOutputPos >= outputLength) {
currentOutputPos = 0xFF; // Mark done
usart_interrupt_disable(UART_PERIF, USART_INT_TBE);
}
}
if (RESET != usart_interrupt_flag_get(UART_PERIF, USART_INT_FLAG_TBE)) {
/* write one byte to the transmit data register */
usart_data_transmit(UART_PERIF, uartOutputBuffer[currentOutputPos++]);
if (currentOutputPos >= outputLength) {
currentOutputPos = 0xFF; // Mark done
usart_interrupt_disable(UART_PERIF, USART_INT_TBE);
}
}
}

View File

@@ -12,349 +12,337 @@ SemaphoreHandle_t FRToSI2C::I2CSemaphore = nullptr;
StaticSemaphore_t FRToSI2C::xSemaphoreBuffer;
#define I2C_TIME_OUT (uint16_t)(12000)
void FRToSI2C::CpltCallback() {
// TODO
// TODO
}
bool FRToSI2C::I2C_RegisterWrite(uint8_t address, uint8_t reg, uint8_t data) {
return Mem_Write(address, reg, &data, 1);
}
bool FRToSI2C::I2C_RegisterWrite(uint8_t address, uint8_t reg, uint8_t data) { return Mem_Write(address, reg, &data, 1); }
uint8_t FRToSI2C::I2C_RegisterRead(uint8_t add, uint8_t reg) {
uint8_t temp = 0;
Mem_Read(add, reg, &temp, 1);
return temp;
uint8_t temp = 0;
Mem_Read(add, reg, &temp, 1);
return temp;
}
enum i2c_step {
//Write+read steps
Write_start, //Sending start on bus
Write_device_address, //start sent, send device address
Write_device_memory_address, //device address sent, write the memory location
Write_device_data_start, // Write all of the remaining data using DMA
Write_device_data_finish, // Write all of the remaining data using DMA
// Write+read steps
Write_start, // Sending start on bus
Write_device_address, // start sent, send device address
Write_device_memory_address, // device address sent, write the memory location
Write_device_data_start, // Write all of the remaining data using DMA
Write_device_data_finish, // Write all of the remaining data using DMA
Read_start, //second read
Read_device_address, // Send device address again for the read
Read_device_data_start, //read device data via DMA
Read_device_data_finish, //read device data via DMA
Send_stop, // send the stop at the end of the transaction
Wait_stop, // Wait for stop to send and we are done
Done, //Finished
Error_occured, //Error occured on the bus
Read_start, // second read
Read_device_address, // Send device address again for the read
Read_device_data_start, // read device data via DMA
Read_device_data_finish, // read device data via DMA
Send_stop, // send the stop at the end of the transaction
Wait_stop, // Wait for stop to send and we are done
Done, // Finished
Error_occured, // Error occured on the bus
};
struct i2c_state {
i2c_step currentStep;
bool isMemoryWrite;
bool wakePart;
uint8_t deviceAddress;
uint8_t memoryAddress;
uint8_t * buffer;
uint16_t numberOfBytes;
dma_parameter_struct dma_init_struct;
i2c_step currentStep;
bool isMemoryWrite;
bool wakePart;
uint8_t deviceAddress;
uint8_t memoryAddress;
uint8_t * buffer;
uint16_t numberOfBytes;
dma_parameter_struct dma_init_struct;
};
volatile i2c_state currentState;
void perform_i2c_step() {
//Performs next step of the i2c state machine
if (i2c_flag_get(I2C0, I2C_FLAG_AERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_AERR);
//Arb error - we lost the bus / nacked
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_BERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_BERR);
// Bus Error
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_LOSTARB)) {
i2c_flag_clear(I2C0, I2C_FLAG_LOSTARB);
// Bus Error
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_PECERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_PECERR);
// Bus Error
currentState.currentStep = Error_occured;
}
switch (currentState.currentStep) {
case Error_occured:
i2c_stop_on_bus(I2C0);
break;
case Write_start:
// Performs next step of the i2c state machine
if (i2c_flag_get(I2C0, I2C_FLAG_AERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_AERR);
// Arb error - we lost the bus / nacked
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_BERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_BERR);
// Bus Error
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_LOSTARB)) {
i2c_flag_clear(I2C0, I2C_FLAG_LOSTARB);
// Bus Error
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_PECERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_PECERR);
// Bus Error
currentState.currentStep = Error_occured;
}
switch (currentState.currentStep) {
case Error_occured:
i2c_stop_on_bus(I2C0);
break;
case Write_start:
/* enable acknowledge */
i2c_ack_config(I2C0, I2C_ACK_ENABLE);
/* i2c master sends start signal only when the bus is idle */
if (!i2c_flag_get(I2C0, I2C_FLAG_I2CBSY)) {
/* send the start signal */
i2c_start_on_bus(I2C0);
currentState.currentStep = Write_device_address;
}
break;
/* enable acknowledge */
i2c_ack_config(I2C0, I2C_ACK_ENABLE);
/* i2c master sends start signal only when the bus is idle */
if (!i2c_flag_get(I2C0, I2C_FLAG_I2CBSY)) {
/* send the start signal */
i2c_start_on_bus(I2C0);
currentState.currentStep = Write_device_address;
}
break;
case Write_device_address:
/* i2c master sends START signal successfully */
if (i2c_flag_get(I2C0, I2C_FLAG_SBSEND)) {
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
i2c_master_addressing(I2C0, currentState.deviceAddress, I2C_TRANSMITTER);
currentState.currentStep = Write_device_memory_address;
}
break;
case Write_device_memory_address:
//Send the device memory location
case Write_device_address:
/* i2c master sends START signal successfully */
if (i2c_flag_get(I2C0, I2C_FLAG_SBSEND)) {
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
i2c_master_addressing(I2C0, currentState.deviceAddress, I2C_TRANSMITTER);
currentState.currentStep = Write_device_memory_address;
}
break;
case Write_device_memory_address:
// Send the device memory location
if (i2c_flag_get(I2C0, I2C_FLAG_ADDSEND)) { //addr sent
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
if (i2c_flag_get(I2C0, I2C_FLAG_ADDSEND)) { // addr sent
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
if (i2c_flag_get(I2C0, I2C_FLAG_BERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_BERR);
// Bus Error
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_AERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_AERR);
//Arb error - we lost the bus / nacked
currentState.currentStep = Error_occured;
} else if (currentState.wakePart) {
//We are stopping here
currentState.currentStep = Send_stop;
} else if (i2c_flag_get(I2C0, I2C_FLAG_TBE)) {
// Write out the 8 byte address
i2c_data_transmit(I2C0, currentState.memoryAddress);
if (i2c_flag_get(I2C0, I2C_FLAG_BERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_BERR);
// Bus Error
currentState.currentStep = Error_occured;
} else if (i2c_flag_get(I2C0, I2C_FLAG_AERR)) {
i2c_flag_clear(I2C0, I2C_FLAG_AERR);
// Arb error - we lost the bus / nacked
currentState.currentStep = Error_occured;
} else if (currentState.wakePart) {
// We are stopping here
currentState.currentStep = Send_stop;
} else if (i2c_flag_get(I2C0, I2C_FLAG_TBE)) {
// Write out the 8 byte address
i2c_data_transmit(I2C0, currentState.memoryAddress);
if (currentState.isMemoryWrite) {
currentState.currentStep = Write_device_data_start;
} else {
currentState.currentStep = Read_start;
}
}
}
if (currentState.isMemoryWrite) {
currentState.currentStep = Write_device_data_start;
} else {
currentState.currentStep = Read_start;
}
}
}
break;
case Write_device_data_start:
break;
case Write_device_data_start:
/* wait until BTC bit is set */
if (i2c_flag_get(I2C0, I2C_FLAG_BTC)) {
/* enable I2C0 DMA */
i2c_dma_enable(I2C0, I2C_DMA_ON);
/* enable DMA0 channel5 */
dma_channel_enable(DMA0, DMA_CH5);
currentState.currentStep = Write_device_data_finish;
}
break;
/* wait until BTC bit is set */
if (i2c_flag_get(I2C0, I2C_FLAG_BTC)) {
/* enable I2C0 DMA */
i2c_dma_enable(I2C0, I2C_DMA_ON);
/* enable DMA0 channel5 */
dma_channel_enable(DMA0, DMA_CH5);
currentState.currentStep = Write_device_data_finish;
}
break;
case Write_device_data_finish: //Wait for complete then goto stop
/* wait until BTC bit is set */
if (dma_flag_get(DMA0, DMA_CH5, DMA_FLAG_FTF)) {
/* wait until BTC bit is set */
if (i2c_flag_get(I2C0, I2C_FLAG_BTC)) {
currentState.currentStep = Send_stop;
}
}
break;
case Read_start:
/* wait until BTC bit is set */
if (i2c_flag_get(I2C0, I2C_FLAG_BTC)) {
i2c_start_on_bus(I2C0);
currentState.currentStep = Read_device_address;
}
break;
case Read_device_address:
if (i2c_flag_get(I2C0, I2C_FLAG_SBSEND)) {
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
i2c_master_addressing(I2C0, currentState.deviceAddress, I2C_RECEIVER);
currentState.currentStep = Read_device_data_start;
}
break;
case Read_device_data_start:
if (i2c_flag_get(I2C0, I2C_FLAG_ADDSEND)) { //addr sent
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
if (i2c_flag_get(I2C0, I2C_FLAG_AERR)) {
//Arb error - we lost the bus / nacked
currentState.currentStep = Error_occured;
}
/* one byte master reception procedure (polling) */
if (currentState.numberOfBytes == 0) {
currentState.currentStep = Send_stop;
} else if (currentState.numberOfBytes == 1) {
/* disable acknowledge */
i2c_ack_config(I2C0, I2C_ACK_DISABLE);
/* clear ADDSEND register by reading I2C_STAT0 then I2C_STAT1 register
* (I2C_STAT0 has already been read) */
i2c_flag_get(I2C0, I2C_FLAG_ADDSEND); //sat0
i2c_flag_get(I2C0, I2C_FLAG_I2CBSY); //sat1
/* send a stop condition to I2C bus*/
i2c_stop_on_bus(I2C0);
/* wait for the byte to be received */
while (!i2c_flag_get(I2C0, I2C_FLAG_RBNE))
;
/* read the byte received from the EEPROM */
*currentState.buffer = i2c_data_receive(I2C0);
currentState.currentStep = Wait_stop;
} else { /* more than one byte master reception procedure (DMA) */
/* enable I2C0 DMA */
i2c_dma_enable(I2C0, I2C_DMA_ON);
/* enable DMA0 channel5 */
dma_channel_enable(DMA0, DMA_CH6);
currentState.currentStep = Read_device_data_finish;
}
}
break;
case Read_device_data_finish: //Wait for complete then goto stop
/* wait until BTC bit is set */
if (dma_flag_get(DMA0, DMA_CH6, DMA_FLAG_FTF)) {
currentState.currentStep = Send_stop;
}
case Write_device_data_finish: // Wait for complete then goto stop
/* wait until BTC bit is set */
if (dma_flag_get(DMA0, DMA_CH5, DMA_FLAG_FTF)) {
/* wait until BTC bit is set */
if (i2c_flag_get(I2C0, I2C_FLAG_BTC)) {
currentState.currentStep = Send_stop;
}
}
break;
case Read_start:
/* wait until BTC bit is set */
if (i2c_flag_get(I2C0, I2C_FLAG_BTC)) {
i2c_start_on_bus(I2C0);
currentState.currentStep = Read_device_address;
}
break;
case Read_device_address:
if (i2c_flag_get(I2C0, I2C_FLAG_SBSEND)) {
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
i2c_master_addressing(I2C0, currentState.deviceAddress, I2C_RECEIVER);
currentState.currentStep = Read_device_data_start;
}
break;
case Read_device_data_start:
if (i2c_flag_get(I2C0, I2C_FLAG_ADDSEND)) { // addr sent
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
if (i2c_flag_get(I2C0, I2C_FLAG_AERR)) {
// Arb error - we lost the bus / nacked
currentState.currentStep = Error_occured;
}
/* one byte master reception procedure (polling) */
if (currentState.numberOfBytes == 0) {
currentState.currentStep = Send_stop;
} else if (currentState.numberOfBytes == 1) {
/* disable acknowledge */
i2c_ack_config(I2C0, I2C_ACK_DISABLE);
/* clear ADDSEND register by reading I2C_STAT0 then I2C_STAT1 register
* (I2C_STAT0 has already been read) */
i2c_flag_get(I2C0, I2C_FLAG_ADDSEND); // sat0
i2c_flag_get(I2C0, I2C_FLAG_I2CBSY); // sat1
/* send a stop condition to I2C bus*/
i2c_stop_on_bus(I2C0);
/* wait for the byte to be received */
while (!i2c_flag_get(I2C0, I2C_FLAG_RBNE))
;
/* read the byte received from the EEPROM */
*currentState.buffer = i2c_data_receive(I2C0);
currentState.currentStep = Wait_stop;
} else { /* more than one byte master reception procedure (DMA) */
/* enable I2C0 DMA */
i2c_dma_enable(I2C0, I2C_DMA_ON);
/* enable DMA0 channel5 */
dma_channel_enable(DMA0, DMA_CH6);
currentState.currentStep = Read_device_data_finish;
}
}
break;
case Read_device_data_finish: // Wait for complete then goto stop
/* wait until BTC bit is set */
if (dma_flag_get(DMA0, DMA_CH6, DMA_FLAG_FTF)) {
currentState.currentStep = Send_stop;
}
break;
case Send_stop:
/* send a stop condition to I2C bus*/
i2c_stop_on_bus(I2C0);
currentState.currentStep = Wait_stop;
break;
case Wait_stop:
/* i2c master sends STOP signal successfully */
if ((I2C_CTL0(I2C0) & 0x0200) != 0x0200) {
currentState.currentStep = Done;
}
break;
default:
//If we get here something is amiss
return;
}
break;
case Send_stop:
/* send a stop condition to I2C bus*/
i2c_stop_on_bus(I2C0);
currentState.currentStep = Wait_stop;
break;
case Wait_stop:
/* i2c master sends STOP signal successfully */
if ((I2C_CTL0(I2C0) & 0x0200) != 0x0200) {
currentState.currentStep = Done;
}
break;
default:
// If we get here something is amiss
return;
}
}
bool perform_i2c_transaction(uint16_t DevAddress, uint16_t memory_address, uint8_t *p_buffer, uint16_t number_of_byte, bool isWrite, bool isWakeOnly) {
{
//TODO is this required
/* disable I2C0 */
i2c_disable(I2C0);
/* enable I2C0 */
i2c_enable(I2C0);
}
i2c_interrupt_disable(I2C0, I2C_INT_ERR);
i2c_interrupt_disable(I2C0, I2C_INT_BUF);
i2c_interrupt_disable(I2C0, I2C_INT_EV);
{
// TODO is this required
/* disable I2C0 */
i2c_disable(I2C0);
/* enable I2C0 */
i2c_enable(I2C0);
}
i2c_interrupt_disable(I2C0, I2C_INT_ERR);
i2c_interrupt_disable(I2C0, I2C_INT_BUF);
i2c_interrupt_disable(I2C0, I2C_INT_EV);
currentState.isMemoryWrite = isWrite;
currentState.wakePart = isWakeOnly;
currentState.deviceAddress = DevAddress;
currentState.memoryAddress = memory_address;
currentState.numberOfBytes = number_of_byte;
currentState.buffer = p_buffer;
if (!isWakeOnly) {
//Setup DMA
currentState.dma_init_struct.memory_width = DMA_MEMORY_WIDTH_8BIT;
currentState.dma_init_struct.memory_addr = (uint32_t) p_buffer;
currentState.dma_init_struct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
currentState.dma_init_struct.number = number_of_byte;
currentState.dma_init_struct.periph_addr = (uint32_t) &I2C_DATA(I2C0);
currentState.dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
currentState.dma_init_struct.periph_width = DMA_PERIPHERAL_WIDTH_8BIT;
currentState.dma_init_struct.priority = DMA_PRIORITY_ULTRA_HIGH;
if (currentState.isMemoryWrite) {
dma_deinit(DMA0, DMA_CH5);
currentState.dma_init_struct.direction = DMA_MEMORY_TO_PERIPHERAL;
dma_init(DMA0, DMA_CH5, (dma_parameter_struct*) &currentState.dma_init_struct);
} else {
dma_deinit(DMA0, DMA_CH6);
currentState.dma_init_struct.direction = DMA_PERIPHERAL_TO_MEMORY;
dma_init(DMA0, DMA_CH6, (dma_parameter_struct*) &currentState.dma_init_struct);
}
currentState.isMemoryWrite = isWrite;
currentState.wakePart = isWakeOnly;
currentState.deviceAddress = DevAddress;
currentState.memoryAddress = memory_address;
currentState.numberOfBytes = number_of_byte;
currentState.buffer = p_buffer;
if (!isWakeOnly) {
// Setup DMA
currentState.dma_init_struct.memory_width = DMA_MEMORY_WIDTH_8BIT;
currentState.dma_init_struct.memory_addr = (uint32_t)p_buffer;
currentState.dma_init_struct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
currentState.dma_init_struct.number = number_of_byte;
currentState.dma_init_struct.periph_addr = (uint32_t)&I2C_DATA(I2C0);
currentState.dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
currentState.dma_init_struct.periph_width = DMA_PERIPHERAL_WIDTH_8BIT;
currentState.dma_init_struct.priority = DMA_PRIORITY_ULTRA_HIGH;
if (currentState.isMemoryWrite) {
dma_deinit(DMA0, DMA_CH5);
currentState.dma_init_struct.direction = DMA_MEMORY_TO_PERIPHERAL;
dma_init(DMA0, DMA_CH5, (dma_parameter_struct *)&currentState.dma_init_struct);
} else {
dma_deinit(DMA0, DMA_CH6);
currentState.dma_init_struct.direction = DMA_PERIPHERAL_TO_MEMORY;
dma_init(DMA0, DMA_CH6, (dma_parameter_struct *)&currentState.dma_init_struct);
}
if (!currentState.isMemoryWrite) {
i2c_dma_last_transfer_config(I2C0, I2C_DMALST_ON);
}
}
//Clear flags
I2C_STAT0(I2C0) = 0;
I2C_STAT1(I2C0) = 0;
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
if (!currentState.isMemoryWrite) {
i2c_dma_last_transfer_config(I2C0, I2C_DMALST_ON);
}
}
// Clear flags
I2C_STAT0(I2C0) = 0;
I2C_STAT1(I2C0) = 0;
i2c_flag_clear(I2C0, I2C_FLAG_ADDSEND);
currentState.currentStep = Write_start; //Always start in write mode
TickType_t timeout = xTaskGetTickCount() + TICKS_SECOND;
while ((currentState.currentStep != Done) && (currentState.currentStep != Error_occured)) {
if (xTaskGetTickCount() > timeout) {
i2c_stop_on_bus(I2C0);
return false;
}
perform_i2c_step();
}
return true;
currentState.currentStep = Write_start; // Always start in write mode
TickType_t timeout = xTaskGetTickCount() + TICKS_SECOND;
while ((currentState.currentStep != Done) && (currentState.currentStep != Error_occured)) {
if (xTaskGetTickCount() > timeout) {
i2c_stop_on_bus(I2C0);
return false;
}
perform_i2c_step();
}
return true;
}
bool FRToSI2C::Mem_Read(uint16_t DevAddress, uint16_t read_address, uint8_t *p_buffer, uint16_t number_of_byte) {
if (!lock())
return false;
bool res = perform_i2c_transaction(DevAddress, read_address, p_buffer, number_of_byte, false, false);
if (!res) {
I2C_Unstick();
}
unlock();
return res;
if (!lock())
return false;
bool res = perform_i2c_transaction(DevAddress, read_address, p_buffer, number_of_byte, false, false);
if (!res) {
I2C_Unstick();
}
unlock();
return res;
}
bool FRToSI2C::Mem_Write(uint16_t DevAddress, uint16_t MemAddress, uint8_t *p_buffer, uint16_t number_of_byte) {
if (!lock())
return false;
bool res = perform_i2c_transaction(DevAddress, MemAddress, p_buffer, number_of_byte, true, false);
if (!res) {
I2C_Unstick();
}
unlock();
return res;
if (!lock())
return false;
bool res = perform_i2c_transaction(DevAddress, MemAddress, p_buffer, number_of_byte, true, false);
if (!res) {
I2C_Unstick();
}
unlock();
return res;
}
bool FRToSI2C::Transmit(uint16_t DevAddress, uint8_t *pData, uint16_t Size) {
return Mem_Write(DevAddress, pData[0], pData + 1, Size - 1);
}
bool FRToSI2C::Transmit(uint16_t DevAddress, uint8_t *pData, uint16_t Size) { return Mem_Write(DevAddress, pData[0], pData + 1, Size - 1); }
bool FRToSI2C::probe(uint16_t DevAddress) {
uint8_t temp[1];
return Mem_Read(DevAddress, 0x00, temp, sizeof(temp));
uint8_t temp[1];
return Mem_Read(DevAddress, 0x00, temp, sizeof(temp));
}
void FRToSI2C::I2C_Unstick() {
unstick_I2C();
}
void FRToSI2C::I2C_Unstick() { unstick_I2C(); }
bool FRToSI2C::lock() {
if (I2CSemaphore == nullptr) {
return false;
}
return xSemaphoreTake(I2CSemaphore, TICKS_SECOND) == pdTRUE;
if (I2CSemaphore == nullptr) {
return false;
}
return xSemaphoreTake(I2CSemaphore, TICKS_SECOND) == pdTRUE;
}
void FRToSI2C::unlock() {
xSemaphoreGive(I2CSemaphore);
}
void FRToSI2C::unlock() { xSemaphoreGive(I2CSemaphore); }
bool FRToSI2C::writeRegistersBulk(const uint8_t address, const I2C_REG *registers, const uint8_t registersLength) {
for (int index = 0; index < registersLength; index++) {
if (!I2C_RegisterWrite(address, registers[index].reg, registers[index].val)) {
return false;
}
if (registers[index].pause_ms) {
delay_ms(registers[index].pause_ms);
}
}
return true;
for (int index = 0; index < registersLength; index++) {
if (!I2C_RegisterWrite(address, registers[index].reg, registers[index].val)) {
return false;
}
if (registers[index].pause_ms) {
delay_ms(registers[index].pause_ms);
}
}
return true;
}
bool FRToSI2C::wakePart(uint16_t DevAddress) {
// wakepart is a special case where only the device address is sent
if (!lock())
return false;
bool res = perform_i2c_transaction(DevAddress, 0, NULL, 0, false, true);
if (!res) {
I2C_Unstick();
}
unlock();
return res;
// wakepart is a special case where only the device address is sent
if (!lock())
return false;
bool res = perform_i2c_transaction(DevAddress, 0, NULL, 0, false, true);
if (!res) {
I2C_Unstick();
}
unlock();
return res;
}
void I2C_EV_IRQ() {
}
void I2C_EV_IRQ() {}
void I2C_ER_IRQ() {
//Error callbacks
// Error callbacks
}