More i2c updates for io
This commit is contained in:
parent
32e0be9802
commit
33033c326b
|
@ -21,246 +21,256 @@
|
|||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "gpio.h"
|
||||
#include "bus_i2c.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
|
||||
// Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7)
|
||||
|
||||
#ifdef SOFT_I2C
|
||||
|
||||
#ifdef SOFT_I2C_PB1011
|
||||
#define SCL_H GPIOB->BSRR = Pin_10
|
||||
#define SCL_L GPIOB->BRR = Pin_10
|
||||
static IO_t scl;
|
||||
static IO_t sda;
|
||||
static volatile uint16_t i2cErrorCount = 0;
|
||||
|
||||
#define SDA_H GPIOB->BSRR = Pin_11
|
||||
#define SDA_L GPIOB->BRR = Pin_11
|
||||
#define SCL_H IOHi(scl)
|
||||
#define SCL_L IOLo(scl)
|
||||
|
||||
#define SCL_read (GPIOB->IDR & Pin_10)
|
||||
#define SDA_read (GPIOB->IDR & Pin_11)
|
||||
#define I2C_PINS (Pin_10 | Pin_11)
|
||||
#define I2C_GPIO GPIOB
|
||||
#endif
|
||||
#define SDA_H IOHi(sda)
|
||||
#define SDA_L IOLo(sda)
|
||||
|
||||
#ifdef SOFT_I2C_PB67
|
||||
#define SCL_H GPIOB->BSRR = Pin_6
|
||||
#define SCL_L GPIOB->BRR = Pin_6
|
||||
#define SCL_read IORead(scl)
|
||||
#define SDA_read IORead(sda)
|
||||
|
||||
#define SDA_H GPIOB->BSRR = Pin_7
|
||||
#define SDA_L GPIOB->BRR = Pin_7
|
||||
|
||||
#define SCL_read (GPIOB->IDR & Pin_6)
|
||||
#define SDA_read (GPIOB->IDR & Pin_7)
|
||||
#define I2C_PINS (Pin_6 | Pin_7)
|
||||
#define I2C_GPIO GPIOB
|
||||
#endif
|
||||
|
||||
#ifndef SCL_H
|
||||
#error Need to define SOFT_I2C_PB1011 or SOFT_I2C_PB67 (see board.h)
|
||||
#if !defined(SOFT_I2C_SCL) || !defined(SOFT_I2C_SDA)
|
||||
#error "Must define the software i2c pins (SOFT_I2C_SCL and SOFT_I2C_SDA) in target.h"
|
||||
#endif
|
||||
|
||||
static void I2C_delay(void)
|
||||
{
|
||||
volatile int i = 7;
|
||||
while (i) {
|
||||
i--;
|
||||
}
|
||||
volatile int i = 7;
|
||||
while (i) {
|
||||
i--;
|
||||
}
|
||||
}
|
||||
|
||||
static bool I2C_Start(void)
|
||||
{
|
||||
SDA_H;
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (!SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
return false;
|
||||
SDA_H;
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (!SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
return true;
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
return true;
|
||||
}
|
||||
|
||||
static void I2C_Stop(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
}
|
||||
|
||||
static void I2C_Ack(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
}
|
||||
|
||||
static void I2C_NoAck(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
}
|
||||
|
||||
static bool I2C_WaitAck(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
SCL_L;
|
||||
return false;
|
||||
}
|
||||
SCL_L;
|
||||
return true;
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
SCL_L;
|
||||
return false;
|
||||
}
|
||||
SCL_L;
|
||||
return true;
|
||||
}
|
||||
|
||||
static void I2C_SendByte(uint8_t byte)
|
||||
{
|
||||
uint8_t i = 8;
|
||||
while (i--) {
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
if (byte & 0x80) {
|
||||
SDA_H;
|
||||
} else {
|
||||
SDA_L;
|
||||
}
|
||||
byte <<= 1;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
}
|
||||
SCL_L;
|
||||
uint8_t i = 8;
|
||||
while (i--) {
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
if (byte & 0x80) {
|
||||
SDA_H;
|
||||
}
|
||||
else {
|
||||
SDA_L;
|
||||
}
|
||||
byte <<= 1;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
}
|
||||
SCL_L;
|
||||
}
|
||||
|
||||
static uint8_t I2C_ReceiveByte(void)
|
||||
{
|
||||
uint8_t i = 8;
|
||||
uint8_t byte = 0;
|
||||
uint8_t i = 8;
|
||||
uint8_t byte = 0;
|
||||
|
||||
SDA_H;
|
||||
while (i--) {
|
||||
byte <<= 1;
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
byte |= 0x01;
|
||||
}
|
||||
}
|
||||
SCL_L;
|
||||
return byte;
|
||||
SDA_H;
|
||||
while (i--) {
|
||||
byte <<= 1;
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
byte |= 0x01;
|
||||
}
|
||||
}
|
||||
SCL_L;
|
||||
return byte;
|
||||
}
|
||||
|
||||
void i2cInit(I2C_TypeDef * I2C)
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
gpio_config_t gpio;
|
||||
UNUSED(device);
|
||||
|
||||
gpio.pin = I2C_PINS;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_OD;
|
||||
gpioInit(I2C_GPIO, &gpio);
|
||||
scl = IOGetByTag(IO_TAG(SOFT_I2C_SCL));
|
||||
sda = IOGetByTag(IO_TAG(SOFT_I2C_SDA));
|
||||
|
||||
IOConfigGPIO(scl, IOCFG_OUT_OD);
|
||||
IOConfigGPIO(sda, IOCFG_OUT_OD);
|
||||
}
|
||||
|
||||
bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
|
||||
{
|
||||
int i;
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
int i;
|
||||
if (!I2C_Start()) {
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
for (i = 0; i < len; i++) {
|
||||
I2C_SendByte(data[i]);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
for (i = 0; i < len; i++) {
|
||||
I2C_SendByte(data[i]);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data)
|
||||
{
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_SendByte(data);
|
||||
I2C_WaitAck();
|
||||
I2C_Stop();
|
||||
return true;
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_SendByte(data);
|
||||
I2C_WaitAck();
|
||||
I2C_Stop();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
|
||||
{
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_Start();
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
|
||||
I2C_WaitAck();
|
||||
while (len) {
|
||||
*buf = I2C_ReceiveByte();
|
||||
if (len == 1) {
|
||||
I2C_NoAck();
|
||||
} else {
|
||||
I2C_Ack();
|
||||
}
|
||||
buf++;
|
||||
len--;
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_Start();
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
|
||||
I2C_WaitAck();
|
||||
while (len) {
|
||||
*buf = I2C_ReceiveByte();
|
||||
if (len == 1) {
|
||||
I2C_NoAck();
|
||||
}
|
||||
else {
|
||||
I2C_Ack();
|
||||
}
|
||||
buf++;
|
||||
len--;
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t i2cGetErrorCounter(void)
|
||||
{
|
||||
// TODO maybe fix this, but since this is test code, doesn't matter.
|
||||
return 0;
|
||||
return i2cErrorCount;
|
||||
}
|
||||
|
||||
bool i2cWriteBufferByDevice(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||
{
|
||||
return i2cWriteBuffer(addr_, reg_, len_, data);
|
||||
}
|
||||
|
||||
bool i2cWriteByDevice(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
|
||||
{
|
||||
return i2cWrite(addr_, reg, data);
|
||||
}
|
||||
|
||||
bool i2cReadByDevice(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
return i2cRead(addr_, reg, len, buf);
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -355,6 +355,8 @@ void i2c_ev_handler(I2CDevice device) {
|
|||
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
I2Cx_device = device;
|
||||
|
||||
if (device == I2CINVALID)
|
||||
return;
|
||||
|
||||
|
|
|
@ -25,303 +25,247 @@
|
|||
|
||||
#include "gpio.h"
|
||||
#include "system.h"
|
||||
#include "drivers/io_impl.h"
|
||||
|
||||
#include "bus_i2c.h"
|
||||
|
||||
#ifndef SOFT_I2C
|
||||
|
||||
#define I2C1_SCL_GPIO GPIOB
|
||||
#define I2C1_SCL_GPIO_AF GPIO_AF_4
|
||||
#define I2C1_SCL_PIN GPIO_Pin_6
|
||||
#define I2C1_SCL_PIN_SOURCE GPIO_PinSource6
|
||||
#define I2C1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB
|
||||
#define I2C1_SDA_GPIO GPIOB
|
||||
#define I2C1_SDA_GPIO_AF GPIO_AF_4
|
||||
#define I2C1_SDA_PIN GPIO_Pin_7
|
||||
#define I2C1_SDA_PIN_SOURCE GPIO_PinSource7
|
||||
#define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB
|
||||
|
||||
#if !defined(I2C2_SCL_GPIO)
|
||||
#define I2C2_SCL_GPIO GPIOF
|
||||
#define I2C2_SCL_GPIO_AF GPIO_AF_4
|
||||
#define I2C2_SCL_PIN GPIO_Pin_6
|
||||
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource6
|
||||
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOF
|
||||
#define I2C2_SDA_GPIO GPIOA
|
||||
#define I2C2_SDA_GPIO_AF GPIO_AF_4
|
||||
#define I2C2_SDA_PIN GPIO_Pin_10
|
||||
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
|
||||
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
||||
#define I2C_GPIO_AF GPIO_AF_4
|
||||
|
||||
#ifndef I2C1_SCL
|
||||
#define I2C1_SCL PB6
|
||||
#endif
|
||||
#ifndef I2C1_SDA
|
||||
#define I2C1_SDA PB7
|
||||
#endif
|
||||
#ifndef I2C2_SCL
|
||||
#define I2C2_SCL PF4
|
||||
#endif
|
||||
#ifndef I2C2_SDA
|
||||
#define I2C2_SDA PA10
|
||||
#endif
|
||||
|
||||
static uint32_t i2cTimeout;
|
||||
|
||||
static volatile uint16_t i2c1ErrorCount = 0;
|
||||
static volatile uint16_t i2c2ErrorCount = 0;
|
||||
static volatile uint16_t i2cErrorCount = 0;
|
||||
//static volatile uint16_t i2c2ErrorCount = 0;
|
||||
|
||||
static I2C_TypeDef *I2Cx = NULL;
|
||||
static i2cDevice_t i2cHardwareMap[] = {
|
||||
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false },
|
||||
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false }
|
||||
};
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
// I2C TimeoutUserCallback
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
uint32_t i2cTimeoutUserCallback(I2C_TypeDef *I2Cx)
|
||||
uint32_t i2cTimeoutUserCallback(void)
|
||||
{
|
||||
if (I2Cx == I2C1) {
|
||||
i2c1ErrorCount++;
|
||||
} else {
|
||||
i2c2ErrorCount++;
|
||||
}
|
||||
return false;
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
|
||||
void i2cInitPort(I2C_TypeDef *I2Cx)
|
||||
static I2CDevice I2Cx_device;
|
||||
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
I2C_InitTypeDef I2C_InitStructure;
|
||||
I2Cx_device = device;
|
||||
|
||||
i2cDevice_t *i2c;
|
||||
i2c = &(i2cHardwareMap[device]);
|
||||
|
||||
if (I2Cx == I2C1) {
|
||||
RCC_AHBPeriphClockCmd(I2C1_SCL_CLK_SOURCE | I2C1_SDA_CLK_SOURCE, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
|
||||
RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2c->dev;
|
||||
|
||||
IO_t scl = IOGetByTag(i2c->scl);
|
||||
IO_t sda = IOGetByTag(i2c->sda);
|
||||
|
||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||
|
||||
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
|
||||
IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
|
||||
IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
|
||||
|
||||
GPIO_PinAFConfig(I2C1_SCL_GPIO, I2C1_SCL_PIN_SOURCE, I2C1_SCL_GPIO_AF);
|
||||
GPIO_PinAFConfig(I2C1_SDA_GPIO, I2C1_SDA_PIN_SOURCE, I2C1_SDA_GPIO_AF);
|
||||
I2C_InitTypeDef i2cInit = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
|
||||
.I2C_DigitalFilter = 0x00,
|
||||
.I2C_OwnAddress1 = 0x00,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_Timing = 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
//.I2C_Timing = 0x8000050B;
|
||||
};
|
||||
|
||||
if (i2c->overClock) {
|
||||
i2cInit.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
||||
}
|
||||
I2C_Init(I2Cx, &i2cInit);
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
I2C_StructInit(&I2C_InitStructure);
|
||||
|
||||
// Init pins
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = I2C1_SCL_PIN;
|
||||
GPIO_Init(I2C1_SCL_GPIO, &GPIO_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = I2C1_SDA_PIN;
|
||||
GPIO_Init(I2C1_SDA_GPIO, &GPIO_InitStructure);
|
||||
|
||||
I2C_StructInit(&I2C_InitStructure);
|
||||
|
||||
I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
I2C_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
I2C_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
I2C_InitStructure.I2C_OwnAddress1 = 0x00;
|
||||
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
|
||||
//I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 100, Hold 10.
|
||||
//I2C_InitStructure.I2C_Timing = 0x0070123D; // 800 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 50, Hold 5.
|
||||
I2C_InitStructure.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
||||
|
||||
|
||||
I2C_Init(I2C1, &I2C_InitStructure);
|
||||
|
||||
I2C_Cmd(I2C1, ENABLE);
|
||||
}
|
||||
|
||||
if (I2Cx == I2C2) {
|
||||
RCC_AHBPeriphClockCmd(I2C2_SCL_CLK_SOURCE | I2C2_SDA_CLK_SOURCE, ENABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
|
||||
RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
|
||||
|
||||
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
|
||||
|
||||
GPIO_PinAFConfig(I2C2_SCL_GPIO, I2C2_SCL_PIN_SOURCE, I2C2_SCL_GPIO_AF);
|
||||
GPIO_PinAFConfig(I2C2_SDA_GPIO, I2C2_SDA_PIN_SOURCE, I2C2_SDA_GPIO_AF);
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
I2C_StructInit(&I2C_InitStructure);
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = I2C2_SCL_PIN;
|
||||
GPIO_Init(I2C2_SCL_GPIO, &GPIO_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = I2C2_SDA_PIN;
|
||||
GPIO_Init(I2C2_SDA_GPIO, &GPIO_InitStructure);
|
||||
|
||||
I2C_StructInit(&I2C_InitStructure);
|
||||
|
||||
I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
I2C_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
I2C_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
I2C_InitStructure.I2C_OwnAddress1 = 0x00;
|
||||
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
|
||||
//I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 100, Hold 10.
|
||||
//I2C_InitStructure.I2C_Timing = 0x0070123D; // 800 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 50, Hold 5.
|
||||
I2C_InitStructure.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
||||
|
||||
I2C_Init(I2C2, &I2C_InitStructure);
|
||||
|
||||
I2C_Cmd(I2C2, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
void i2cInit(I2CDevice index)
|
||||
{
|
||||
if (index == I2CDEV_1) {
|
||||
I2Cx = I2C1;
|
||||
} else {
|
||||
I2Cx = I2C2;
|
||||
}
|
||||
i2cInitPort(I2Cx);
|
||||
I2C_Cmd(I2Cx, ENABLE);
|
||||
}
|
||||
|
||||
uint16_t i2cGetErrorCounter(void)
|
||||
{
|
||||
if (I2Cx == I2C1) {
|
||||
return i2c1ErrorCount;
|
||||
}
|
||||
return i2cErrorCount;
|
||||
}
|
||||
|
||||
return i2c2ErrorCount;
|
||||
bool i2cWriteByDevice(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
|
||||
{
|
||||
addr_ <<= 1;
|
||||
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2cHardwareMap[device].dev;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TCR flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
|
||||
{
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Write data to TXDR */
|
||||
I2C_SendData(I2Cx, data);
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cReadByDevice(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
addr_ <<= 1;
|
||||
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2cHardwareMap[device].dev;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TC flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
|
||||
|
||||
/* Wait until all data are received */
|
||||
while (len) {
|
||||
/* Wait until RXNE flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Read data from RXDR */
|
||||
*buf = I2C_ReceiveData(I2Cx);
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
buf++;
|
||||
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||
{
|
||||
return i2cWriteBufferByDevice(I2Cx_device, addr_, reg_, len_, data);
|
||||
}
|
||||
|
||||
bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
|
||||
{
|
||||
addr_ <<= 1;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TCR flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
|
||||
{
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Write data to TXDR */
|
||||
I2C_SendData(I2Cx, data);
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
return true;
|
||||
return i2cWriteByDevice(I2Cx_device, addr_, reg, data);
|
||||
}
|
||||
|
||||
bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
addr_ <<= 1;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TC flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
|
||||
|
||||
/* Wait until all data are received */
|
||||
while (len) {
|
||||
/* Wait until RXNE flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Read data from RXDR */
|
||||
*buf = I2C_ReceiveData(I2Cx);
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
buf++;
|
||||
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_DEFAULT_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback(I2Cx);
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
return i2cReadByDevice(I2Cx_device, addr_, reg, len, buf);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue