Intermediate storage point

This commit is contained in:
Lennart Eriksson 2016-09-27 11:35:07 +02:00
parent 7c37ef0b47
commit 30cb13cf49
6 changed files with 468 additions and 85 deletions

View File

@ -10,10 +10,33 @@
#include "stm32f4xx.h"
/******************************************************************************
* BRIEF: Configure the I2C bus to be used *
* INFORMATION: *
******************************************************************************/
void i2c_configure(I2C_TypeDef* i2c, uint16_t sda_pin, uint16_t scl_pin, uint32_t my_address);
void i2c_configure(void);
/******************************************************************************
* BRIEF: Get data over the I2C bus *
* INFORMATION: *
* Since this system uses a 7 bit addressing mode we send the slave address *
* in the first bytes 7 MSbs and then the LSb is set to 1 indicating that *
* it is a receive command, after that the slave responds with a 1 bit ack and *
* the data is sent one byte at a time with an acknowledge in between *
* every byte, as per the standard. Returns true if successful *
******************************************************************************/
bool i2c_receive(uint8_t slave_address, uint8_t* buffer, uint32_t length);
/******************************************************************************
* BRIEF: Send data over the I2C bus *
* INFORMATION: *
* Since this system uses a 7 bit addressing mode we send the slave address *
* in the first bytes 7 MSbs and then the LSb is set to 0 indicating that *
* it is a send command, after that the slave responds with a 1 bit ack and *
* the data is sent one byte at a time with an acknowledge in between *
* every byte, as per the standard. Returns true if successful *
******************************************************************************/
bool i2c_send(uint8_t slave_address, uint8_t* data, uint32_t length);
#endif /* DRIVERS_I2C_H_ */

View File

@ -7,50 +7,93 @@
#include "drivers/I2C.h"
// the I2C handle sending data over
I2C_HandleTypeDef I2C_handle;
void i2c_configure(uint32_t channel)
/******************************************************************************
* BRIEF: Configure the I2C bus to be used *
* INFORMATION: *
******************************************************************************/
void i2c_configure(I2C_TypeDef* i2c, uint16_t sda_pin, uint16_t scl_pin, uint32_t my_address)
{
uint8_t i2c_af;
// get the correct alternate function for the selected I2C
if(i2c == I2C1)
i2c_af = GPIO_AF4_I2C1;
else if(i2c == I2C2)
i2c_af = GPIO_AF4_I2C2;
else if(i2c == I2C3)
i2c_af = GPIO_AF4_I2C3;
else
i2c_af = GPIO_AF4_I2C1;
//Initialize pins for SCL and SDA
GPIO_InitTypeDef GPIO_InitStruct;
I2C_InitTypeDef I2C_InitStruct;
__HAL_RCC_I2C1_CLK_ENABLE();
__GPIOB_CLK_ENABLE();
GPIO_InitStruct.Pin = sda_pin | scl_pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = i2c_af;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
// enable APB1 peripheral clock for I2C1
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
// enable clock for SCL and SDA pins
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
/* setup SCL and SDA pins
* You can connect I2C1 to two different
* pairs of pins:
* 1. SCL on PB6 and SDA on PB7
* 2. SCL on PB8 and SDA on PB9
*/
GPIO_InitStruct.Pin = GPIO_PIN_6 | GPIO_PIN_7; // we are going to use PB6 and PB7
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; // set pins to alternate function
GPIO_InitStruct.Speed = GPIO_SPEED_LOW; // set GPIO speed
// GPIO_InitStruct.GPIO_OType = GPIO_OType_OD; // set output to open drain --> the line has to be only pulled low, not driven high
GPIO_InitStruct.Pull = GPIO_PULLUP; // enable pull up resistors
GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
GPIO_Init(GPIOB, &GPIO_InitStruct); // init GPIOB
I2C_InitStruct.ClockSpeed = 100000;
I2C_InitStruct.DualAddressMode =
// Connect I2C1 pins to AF
GPIO_PinAFConfig(GPIOB, GPIO_PinSource6, GPIO_AF_I2C1); // SCL
GPIO_PinAFConfig(GPIOB, GPIO_PinSource7, GPIO_AF_I2C1); // SDA
// configure I2C1
I2C_InitStruct.I2C_ClockSpeed = 100000; // 100kHz
I2C_InitStruct.I2C_Mode = I2C_Mode_I2C; // I2C mode
I2C_InitStruct.I2C_DutyCycle = I2C_DutyCycle_2; // 50% duty cycle --> standard
I2C_InitStruct.I2C_OwnAddress1 = 0x00; // own address, not relevant in master mode
I2C_InitStruct.I2C_Ack = I2C_Ack_Disable; // disable acknowledge when reading (can be changed later on)
I2C_InitStruct.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; // set address length to 7 bit addresses
I2C_Init(I2C1, &I2C_InitStruct); // init I2C1
// enable I2C1
I2C_Cmd(I2C1, ENABLE);
//Initialize I2C communication
I2C_handle.Instance = i2c;
I2C_handle.Init.ClockSpeed = 100000;
I2C_handle.Init.DutyCycle = I2C_DUTYCYCLE_2;
I2C_handle.Init.OwnAddress1 = my_address;
I2C_handle.Init.OwnAddress2 = 0;
I2C_handle.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
I2C_handle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
I2C_handle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
I2C_handle.Init.NoStretchMode = I2C_NOSTRETCH_ENABLE;
HAL_I2C_Init(&I2C_handle);
}
/******************************************************************************
* BRIEF: Get data over the I2C bus *
* INFORMATION: *
* Since this system uses a 7 bit addressing mode we send the slave address *
* in the first bytes 7 MSbs and then the LSb is set to 1 indicating that *
* it is a receive command, after that the slave responds with a 1 bit ack and *
* the data is sent one byte at a time with an acknowledge in between *
* every byte, as per the standard. Returns true if successful *
******************************************************************************/
bool i2c_receive(uint8_t slave_address, uint8_t* buffer, uint32_t length)
{
uint8_t i = 0;
while(HAL_I2C_Master_Receive(&I2C_handle, (slave_address << 1) | 1, buffer, length, 1000)!= HAL_OK && i++ < 10)
{}
while (HAL_I2C_GetState(&I2C_handle) != HAL_I2C_STATE_READY)
{}
return (i < 10);
}
/***************************************************************************
* BRIEF: Send data over the I2C bus *
* INFORMATION: *
* Since this system uses a 7 bit addressing mode we send the slave address *
* in the first bytes 7 MSbs and then the LSb is set to 0 indicating that *
* it is a send command, after that the slave responds with a 1 bit ack and *
* the data is sent one byte at a time with an acknowledge in between *
* every byte, as per the standard. Returns true if successful *
***************************************************************************/
bool i2c_send(uint8_t slave_address, uint8_t* data, uint32_t length)
{
uint8_t i = 0;
// try to send the data 10 times and if no acknowledge is received during these 10 messages we stop trying so that
// the system don't gets stuck forever because a slave is unreachable
while(HAL_I2C_Master_Transmit(&I2C_handle,(slave_address << 1), (uint8_t*)data, length, 1000) != HAL_OK && i++ < 10)
{}
//Wait til the I2C bus is done with all sending
while (HAL_I2C_GetState(&I2C_handle) != HAL_I2C_STATE_READY){}
return (i < 10);
}

View File

@ -0,0 +1,297 @@
//
//#include "stm32f4xx.h"
//
////_____ M A C R O S
//#define TRUE 1
//#define FALSE 0
//#define F_CPU 4000000UL // 4 MHz external XTAL
//#define SCL_CLOCK 100000L // I2C clock in Hz
//#define ADDR_W 0xEE // Module address write mode
//#define ADDR_R 0xEF // Module address read mode
//#define CMD_RESET 0x1E // ADC reset command
//#define CMD_ADC_READ 0x00 // ADC read command
//#define CMD_ADC_CONV 0x40 // ADC conversion command
//#define CMD_ADC_D1 0x00 // ADC D1 conversion
//#define CMD_ADC_D2 0x10 // ADC D2 conversion
//#define CMD_ADC_256 0x00 // ADC OSR=256
//#define CMD_ADC_512 0x02 // ADC OSR=512
//#define CMD_ADC_1024 0x04 // ADC OSR=1024
//#define CMD_ADC_2048 0x06 // ADC OSR=2048
//#define CMD_ADC_4096 0x08 // ADC OSR=4096
//#define CMD_PROM_RD 0xA0 // Prom read command
////_____ I N C L U D E S
//#include <stdio.h>
////#include <util/delay.h>
////#include <util/twi.h>
////#include <avr/io.h>
//#include <math.h>
////_____ D E F I N I T I O N S
//unsigned char i2c_start(unsigned char address);
//void i2c_stop(void);
//unsigned char i2c_write( unsigned char data );
//unsigned char i2c_readAck(void);
//unsigned char i2c_readNak(void);
//void cmd_reset(void);
//unsigned long cmd_adc(char cmd);
//unsigned int cmd_prom(char coef_num);
//unsigned char crc4(unsigned int n_prom[]);
////********************************************************
////! @brief send I2C start condition and the address byte
////!
////! @return 0
////********************************************************
//unsigned char i2c_start(unsigned char address)
//{
// unsigned char twst;
//
// I2C1->CR1 = 1 << 8 | 1 << 0;
//
// TWCR = (1<<TWINT) | (1<<TWSTA) | (1<<TWEN); // send START condition
//
// while(!(TWCR & (1<<TWINT))); // wait until transmission completed
//
// twst = TW_STATUS & 0xF8;// check value of TWI Status Register. Mask prescaler bits.
//
// if ( (twst != TW_START) && (twst != TW_REP_START))
// return 1;
//
// TWDR = address; // send device address
//
// TWCR = (1<<TWINT) | (1<<TWEN);
//
// // wait until transmission completed and ACK/NACK has been received
// while(!(TWCR & (1<<TWINT)));
//
// twst = TW_STATUS & 0xF8;
//
// // check value of TWI Status Register. Mask prescaler bits.
// if ( (twst != TW_MT_SLA_ACK) && (twst != TW_MR_SLA_ACK) )
// return 1;
// return 0;
//}
////********************************************************
////! @brief send I2C stop condition
////!
////! @return none
////********************************************************
//void i2c_stop(void)
//{
///* send stop condition */
//TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWSTO);
//// wait until stop condition is executed and bus released
//while(TWCR & (1<<TWSTO)); //THIS MAKES PROBLEM FOR IS2402
//}
////********************************************************
////! @brief send I2C stop condition
////!
////! @return 0
////********************************************************
//unsigned char i2c_write(unsigned char data)
//{
//unsigned char twst;
//TWDR = data; // send data to the previously addressed device
//TWCR = (1<<TWINT) | (1<<TWEN);
//while(!(TWCR & (1<<TWINT))); // wait until transmission completed
//twst = TW_STATUS & 0xF8; // check value of TWI Status Register. Mask prescaler bits
//if( twst != TW_MT_DATA_ACK) return 1;
//return 0;
//}
////********************************************************
////! @brief read I2C byte with acknowledgment
////!
////! @return read byte
////********************************************************
//unsigned char i2c_readAck(void)
//{
//TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWEA);
//while(!(TWCR & (1<<TWINT)));
//return TWDR;
//}
////********************************************************
////! @brief read I2C byte without acknowledgment
////!
////! @return read byte
////********************************************************
//unsigned char i2c_readNak(void)
//{
//TWCR = (1<<TWINT) | (1<<TWEN);
//while(!(TWCR & (1<<TWINT)));
//return TWDR;
//} //********************************************************
////! @brief send command using I2C hardware interface
////!
////! @return none
////********************************************************
//void i2c_send(char cmd)
//{
//unsigned char ret;
//ret = i2c_start(ADDR_W); // set device address and write mode
//if ( ret )
//{//failed to issue start condition, possibly no device found */
//i2c_stop();
//}
//else
//{// issuing start condition ok, device accessible
//ret=i2c_write(cmd);
//i2c_stop();
//}
//}
////********************************************************
////! @brief send reset sequence
////!
////! @return none
////********************************************************
//void cmd_reset(void)
//{
//i2c_send(CMD_RESET); // send reset sequence
//_delay_ms(3); // wait for the reset sequence timing
//}
////********************************************************
////! @brief preform adc conversion
////!
////! @return 24bit result
////********************************************************
//unsigned long cmd_adc(char cmd)
//{
//unsigned int ret;
//unsigned long temp=0;
//i2c_send(CMD_ADC_CONV+cmd); // send conversion command
//switch (cmd & 0x0f) // wait necessary conversion time
//{
//case CMD_ADC_256 : _delay_us(900); break;
//case CMD_ADC_512 : _delay_ms(3); break;
//case CMD_ADC_1024: _delay_ms(4); break;
//case CMD_ADC_2048: _delay_ms(6); break;
//case CMD_ADC_4096: _delay_ms(10); break;
//}
//i2c_send(CMD_ADC_READ);
//ret = i2c_start(ADDR_R); // set device address and read mode
//if ( ret )
//{//failed to issue start condition, possibly no device found
//i2c_stop();
//}
//else
//{//issuing start condition ok, device accessible
//ret = i2c_readAck(); // read MSB and acknowledge
//temp=65536*ret;
//ret = i2c_readAck(); // read byte and acknowledge
//temp=temp+256*ret;
//ret = i2c_readNak(); // read LSB and not acknowledge
//temp=temp+ret;
//i2c_stop(); // send stop condition
//}
//return temp;
//}
////********************************************************
////! @brief Read calibration coefficients
////!
////! @return coefficient
////********************************************************
//unsigned int cmd_prom(char coef_num)
//{
//unsigned int ret;
//unsigned int rC=0;
//
//i2c_send(CMD_PROM_RD+coef_num*2); // send PROM READ command
//ret = i2c_start(ADDR_R); // set device address and read mode
//if ( ret )
//{//failed to issue start condition, possibly no device found
//i2c_stop();
//}
//else
//{//issuing start condition ok, device accessible
//ret = i2c_readAck(); // read MSB and acknowledge
//rC=256*ret;
//ret = i2c_readNak(); // read LSB and not acknowledge
//rC=rC+ret;
//i2c_stop();
//}
//return rC;
//}
////********************************************************
////! @brief calculate the CRC code
////!
////! @return crc code
////********************************************************
//unsigned char crc4(unsigned int n_prom[])
//{
//int cnt; // simple counter
//unsigned int n_rem; // crc reminder
//unsigned int crc_read; // original value of the crc
//unsigned char n_bit;
//n_rem = 0x00;
//crc_read=n_prom[7]; //save read CRC
//n_prom[7]=(0xFF00 & (n_prom[7])); //CRC byte is replaced by 0
//for (cnt = 0; cnt < 16; cnt++) // operation is performed on bytes
//{// choose LSB or MSB
//if (cnt%2==1) n_rem ^= (unsigned short) ((n_prom[cnt>>1]) & 0x00FF);
//else n_rem ^= (unsigned short) (n_prom[cnt>>1]>>8);
//for (n_bit = 8; n_bit > 0; n_bit--)
//{
//if (n_rem & (0x8000))
//{
//n_rem = (n_rem << 1) ^ 0x3000; }
//else
//{
//n_rem = (n_rem << 1);
//}
//}
//}
//n_rem= (0x000F & (n_rem >> 12)); // final 4-bit reminder is CRC code
//n_prom[7]=crc_read; // restore the crc_read to its original place
//return (n_rem ^ 0x0);
//}
////********************************************************
////! @brief main program
////!
////! @return 0
////********************************************************
//int main (void)
//{
//unsigned long D1; // ADC value of the pressure conversion
//unsigned long D2; // ADC value of the temperature conversion
//unsigned int C[8]; // calibration coefficients
//double P; // compensated pressure value
//double T; // compensated temperature value
//double dT; // difference between actual and measured temperature
//double OFF; // offset at actual temperature
//double SENS; // sensitivity at actual temperature
//int i;
//unsigned char n_crc; // crc value of the prom
//
//// setup the ports
//DDRA = 0xFE;
//DDRB = 0x0F; //SPI pins as input
//DDRC = 0x03; // I2C pins as output
//DDRD = 0x82; // RS out and tx out;
//
//PORTA = 0x1F; // I2C pin high
//PORTB = 0xF0;
//PORTC = 0x01;
//PORTD = 0x00;
//
//// initialize the I2C hardware module
//TWSR = 0; // no prescaler
//TWBR = ((F_CPU/SCL_CLOCK)-16)/2; // set the I2C speed
//
//D1=0;
//D2=0;
//cmd_reset(); // reset IC
//for (i=0;i<8;i++){ C[i]=cmd_prom(i);} // read coefficients
//n_crc=crc4(C); // calculate the CRC
//for(;;) // loop without stopping
//{
//D2=cmd_adc(CMD_ADC_D2+CMD_ADC_4096); // read D2
//D1=cmd_adc(CMD_ADC_D1+CMD_ADC_4096); // read D1
//// calcualte 1st order pressure and temperature (MS5607 1st order algorithm)
//dT=D2-C[5]*pow(2,8);
//OFF=C[2]*pow(2,17)+dT*C[4]/pow(2,6);
//SENS=C[1]*pow(2,16)+dT*C[3]/pow(2,7);
//
//T=(2000+(dT*C[6])/pow(2,23))/100;
//P=(((D1*SENS)/pow(2,21)-OFF)/pow(2,15))/100;
//// place to use P, T, put them on LCD, send them trough RS232 interface...
//}
//
//return 0;
//}

View File

@ -12,6 +12,7 @@
#include "drivers/adc.h"
#include "drivers/system_clock.h"
#include "drivers/I2C.h"
#include "stm32f4xx.h"
#include "system_variables.h"
#include "utilities.h"
@ -28,59 +29,77 @@ int main(void)
system_clock_config();
int i = 1;
/* COMPAS WORKING
i2c_configure(I2C1, GPIO_PIN_8, GPIO_PIN_9, 0x56);
//Add ADC Channels
adc_pin_add(ADC_CHANNEL_0);
adc_pin_add(ADC_CHANNEL_1);
adc_pin_add(ADC_CHANNEL_12);
//Configure the ADCs
adc_configure();
uint32_t address = 0b00011110;
uint8_t start_request_1[2] = { 0b00000000, 0b01110000 };
uint8_t start_request_2[2] = { 0b00000001, 0b10100000 };
uint8_t start_request_3[2] = { 0b00000010, 0b00000000 };
/* This is done in system_clock_config for all GPIO clocks */
//__GPIOB_CLK_ENABLE();
GPIO_InitTypeDef gpinit;
gpinit.Pin = GPIO_PIN_5;
gpinit.Mode = GPIO_MODE_OUTPUT_PP;
gpinit.Pull = GPIO_PULLUP;
gpinit.Speed = GPIO_SPEED_HIGH;
HAL_GPIO_Init(GPIOB, &gpinit);
uint8_t request_data[1] = { 0b00000110 };
uint8_t reset_pointer_data[1] = { 0b00000011 };
uint8_t response_data[6] = { 0x0 };
adc_start();
int num = 2000;
int j = 0;
volatile uint32_t time_us[num];
i2c_send(address, &start_request_1, 2);
i2c_send(address, &start_request_2, 2);
i2c_send(address, &start_request_3, 2);
// Delay for at least 6 ms for system startup to finish
HAL_Delay(10);
while (1)
{
i++;
i2c_send(address, &request_data, 1);
i2c_receive(address, &response_data, 6);
i2c_send(address, &reset_pointer_data, 1);
//g_ADCValue = accumulate(g_ADCBuffer,ADC_BUFFER_LENGTH) / ADC_BUFFER_LENGTH;
//HAL_Delay(100);
int g_ADCValue = adc_read(ADC_CHANNEL_0);
int g_ADCValue1 = adc_read(ADC_CHANNEL_1);
int g_ADCValue12 = adc_read(ADC_CHANNEL_12);
// HAL_Delay(100);
if(response_data[0] != 0)
response_data[0] = 0;
}
*/
int offTime = g_ADCValue;
int onTime = 4096 - offTime;
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_5,GPIO_PIN_SET);
for (int i = 0; i < onTime; i++)
{
asm("nop");
}
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_5,GPIO_PIN_RESET);
for (int i = 0; i < offTime; i++)
{
asm("nop");
}
//Get time in microseconds
if(j < num)
time_us[j++] = clock_get_us();
i2c_configure(I2C1, GPIO_PIN_8, GPIO_PIN_9, 0x56);
uint32_t address = 0x77;
uint8_t reset_data[1] = { 0x1E };
uint8_t init_data[1] = { 0xA2 };
uint8_t init_rsp_data[2] = { 0x00 };
uint8_t request_data[500] = { 0xFF };
uint8_t response_data[2] = { 0x0 };
// while(count--)
i2c_send(address, address, 1);
i2c_send(reset_data[0], &reset_data, 1);
HAL_Delay(50);
for(int i = 0; i < 6; i++)
{
if(i2c_send(address, &init_data, 1) == true)
i2c_receive(address, &response_data, 2);
init_data[0] += 2;
}
HAL_Delay(20);
while (1)
{
if(i2c_send(address, &request_data, 1) == true)
i2c_receive(address, &response_data, 2);
// HAL_Delay(100);
if(response_data[0] != 0)
response_data[0] = 0;
}
for(;;);

View File

@ -392,7 +392,7 @@
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
#define assert_param(expr) ((expr) ? (void)0 : a,ssert_failed((uint8_t *)__FILE__ __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else

View File

@ -4763,7 +4763,8 @@ static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uin
/* Check for the Timeout */
if(Timeout != HAL_MAX_DELAY)
{
if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout))
uint32_t time = HAL_GetTick();
if((Timeout == 0U)||((time - tickstart ) > Timeout))
{
hi2c->PreviousState = I2C_STATE_NONE;
hi2c->State= HAL_I2C_STATE_READY;