1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 14:55:21 +03:00

Code formatting and style fixes.

This commit is contained in:
Dominic Clifton 2014-05-13 16:00:17 +01:00
parent 4d572800ee
commit 89d2c3152f
17 changed files with 282 additions and 315 deletions

View file

@ -1,4 +1,3 @@
#pragma once #pragma once
#ifndef sq #ifndef sq
@ -9,8 +8,7 @@
#define M_PI 3.14159265358979323846f #define M_PI 3.14159265358979323846f
#endif /* M_PI */ #endif /* M_PI */
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f #define RADX10 (M_PI / 1800.0f) // 0.001745329252f #define RAD (M_PI / 180.0f)
#define RAD (M_PI / 180.0f)
#define DEG2RAD(degrees) (degrees * RAD) #define DEG2RAD(degrees) (degrees * RAD)

View file

@ -12,7 +12,6 @@
#include "accgyro_common.h" #include "accgyro_common.h"
#include "accgyro_l3g4200d.h" #include "accgyro_l3g4200d.h"
// L3G4200D, Standard address 0x68 // L3G4200D, Standard address 0x68
#define L3G4200D_ADDRESS 0x68 #define L3G4200D_ADDRESS 0x68
#define L3G4200D_ID 0xD3 #define L3G4200D_ID 0xD3

View file

@ -39,8 +39,6 @@ extern int16_t debug[4];
#define OUT_TEMP_ADDR 0x26 #define OUT_TEMP_ADDR 0x26
#define OUT_X_L_ADDR 0x28 #define OUT_X_L_ADDR 0x28
#define MODE_ACTIVE ((uint8_t)0x08) #define MODE_ACTIVE ((uint8_t)0x08)
#define OUTPUT_DATARATE_1 ((uint8_t)0x00) #define OUTPUT_DATARATE_1 ((uint8_t)0x00)
@ -65,8 +63,6 @@ extern int16_t debug[4];
#define BOOT ((uint8_t)0x80) #define BOOT ((uint8_t)0x80)
static volatile uint16_t spi1ErrorCount = 0; static volatile uint16_t spi1ErrorCount = 0;
static volatile uint16_t spi2ErrorCount = 0; static volatile uint16_t spi2ErrorCount = 0;
static volatile uint16_t spi3ErrorCount = 0; static volatile uint16_t spi3ErrorCount = 0;
@ -84,18 +80,14 @@ static volatile uint16_t spi3ErrorCount = 0;
uint32_t spiTimeoutUserCallback(SPI_TypeDef *SPIx) uint32_t spiTimeoutUserCallback(SPI_TypeDef *SPIx)
{ {
if (SPIx == SPI1) if (SPIx == SPI1) {
{
spi1ErrorCount++; spi1ErrorCount++;
return spi1ErrorCount; return spi1ErrorCount;
} } else if (SPIx == SPI2) {
else if (SPIx == SPI2)
{
spi2ErrorCount++; spi2ErrorCount++;
return spi2ErrorCount; return spi2ErrorCount;
} } else {
else spi3ErrorCount++;
{ spi3ErrorCount++;
return spi3ErrorCount; return spi3ErrorCount;
} }
} }
@ -152,20 +144,25 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
SPI_Cmd(SPI1, ENABLE); SPI_Cmd(SPI1, ENABLE);
} }
static uint8_t spiTransfer(SPI_TypeDef *SPIx, uint8_t data) static uint8_t spiTransfer(SPI_TypeDef *SPIx, uint8_t data)
{ {
uint16_t spiTimeout; uint16_t spiTimeout;
spiTimeout = 0x1000; spiTimeout = 0x1000;
while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_TXE) == RESET) while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0) return spiTimeoutUserCallback(SPIx); if ((spiTimeout--) == 0) {
return spiTimeoutUserCallback(SPIx);
}
}
SPI_SendData8(SPIx, data); SPI_SendData8(SPIx, data);
spiTimeout = 0x1000; spiTimeout = 0x1000;
while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_RXNE) == RESET) while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_RXNE) == RESET) {
if ((spiTimeout--) == 0) return spiTimeoutUserCallback(SPIx); if ((spiTimeout--) == 0) {
return spiTimeoutUserCallback(SPIx);
}
}
return ((uint8_t) SPI_ReceiveData8(SPIx)); return ((uint8_t) SPI_ReceiveData8(SPIx));
} }

View file

@ -58,7 +58,6 @@ extern int16_t debug[4];
#define CONTINUOUS_CONVERSION 0x00 #define CONTINUOUS_CONVERSION 0x00
uint8_t accelCalibrating = false; uint8_t accelCalibrating = false;
float accelOneG = 9.8065; float accelOneG = 9.8065;
@ -124,5 +123,3 @@ bool lsm303dlhcAccDetect(acc_t *acc)
return true; return true;
} }

View file

@ -19,25 +19,12 @@
#define DMP_MEM_START_ADDR 0x6E #define DMP_MEM_START_ADDR 0x6E
#define DMP_MEM_R_W 0x6F #define DMP_MEM_R_W 0x6F
#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN #define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN #define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN #define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS #define MPU_RA_XA_OFFS_L_TC 0x07
#define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS #define MPU_RA_YA_OFFS_L_TC 0x09
#define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS #define MPU_RA_ZA_OFFS_L_TC 0x0B
#define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN #define MPU_RA_PRODUCT_ID 0x0C // Product ID Register #define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR #define MPU_RA_XG_OFFS_USRL 0x14
#define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN #define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR #define MPU_RA_YG_OFFS_USRL 0x16
#define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN #define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR #define MPU_RA_ZG_OFFS_USRL 0x18
#define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
#define MPU_RA_XA_OFFS_L_TC 0x07
#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
#define MPU_RA_YA_OFFS_L_TC 0x09
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
#define MPU_RA_ZA_OFFS_L_TC 0x0B
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
#define MPU_RA_XG_OFFS_USRL 0x14
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
#define MPU_RA_YG_OFFS_USRL 0x16
#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
#define MPU_RA_ZG_OFFS_USRL 0x18
#define MPU_RA_SMPLRT_DIV 0x19 #define MPU_RA_SMPLRT_DIV 0x19
#define MPU_RA_CONFIG 0x1A #define MPU_RA_CONFIG 0x1A
#define MPU_RA_GYRO_CONFIG 0x1B #define MPU_RA_GYRO_CONFIG 0x1B
@ -109,7 +96,6 @@
#define MPU_RA_WHO_AM_I 0x75 #define MPU_RA_WHO_AM_I 0x75
#define MPU6050_SMPLRT_DIV 0 // 8000Hz #define MPU6050_SMPLRT_DIV 0 // 8000Hz
#define MPU6050_LPF_256HZ 0 #define MPU6050_LPF_256HZ 0
#define MPU6050_LPF_188HZ 1 #define MPU6050_LPF_188HZ 1
#define MPU6050_LPF_98HZ 2 #define MPU6050_LPF_98HZ 2
@ -278,7 +264,8 @@ static void mpu6050GyroInit(void)
delay(5); delay(5);
i2cWrite(MPU6050_ADDRESS, MPU_RA_SMPLRT_DIV, 0x00); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) i2cWrite(MPU6050_ADDRESS, MPU_RA_SMPLRT_DIV, 0x00); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference) i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_PIN_CFG,
0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS
i2cWrite(MPU6050_ADDRESS, MPU_RA_CONFIG, mpuLowPassFilter); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz) i2cWrite(MPU6050_ADDRESS, MPU_RA_CONFIG, mpuLowPassFilter); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
i2cWrite(MPU6050_ADDRESS, MPU_RA_GYRO_CONFIG, 0x18); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec i2cWrite(MPU6050_ADDRESS, MPU_RA_GYRO_CONFIG, 0x18); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec

View file

@ -5,9 +5,7 @@
#include "platform.h" #include "platform.h"
#include "sensors_common.h" // FIXME dependency into the main code #include "sensors_common.h" // FIXME dependency into the main code #include "accgyro_common.h"
#include "accgyro_common.h"
#include "system_common.h" #include "system_common.h"
#include "adc_fy90q.h" #include "adc_fy90q.h"

View file

@ -56,9 +56,7 @@ typedef struct {
#define E_SENSOR_NOT_DETECTED (char) 0 #define E_SENSOR_NOT_DETECTED (char) 0
#define BMP085_PROM_START__ADDR 0xaa #define BMP085_PROM_START__ADDR 0xaa
#define BMP085_PROM_DATA__LEN 22 #define BMP085_PROM_DATA__LEN 22
#define BMP085_T_MEASURE 0x2E // temperature measurent #define BMP085_T_MEASURE 0x2E // temperature measurent #define BMP085_P_MEASURE 0x34 // pressure measurement #define BMP085_CTRL_MEAS_REG 0xF4
#define BMP085_P_MEASURE 0x34 // pressure measurement
#define BMP085_CTRL_MEAS_REG 0xF4
#define BMP085_ADC_OUT_MSB_REG 0xF6 #define BMP085_ADC_OUT_MSB_REG 0xF6
#define BMP085_ADC_OUT_LSB_REG 0xF7 #define BMP085_ADC_OUT_LSB_REG 0xF7
#define BMP085_CHIP_ID__POS 0 #define BMP085_CHIP_ID__POS 0
@ -79,10 +77,7 @@ typedef struct {
#define BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS #define BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS
#define BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK) #define BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK)
#define SMD500_PARAM_MG 3038 //calibration parameter #define SMD500_PARAM_MG 3038 //calibration parameter #define SMD500_PARAM_MH -7357 //calibration parameter #define SMD500_PARAM_MI 3791 //calibration parameter
#define SMD500_PARAM_MH -7357 //calibration parameter
#define SMD500_PARAM_MI 3791 //calibration parameter
static bmp085_t bmp085 = { { 0, } }; static bmp085_t bmp085 = { { 0, } };
static bool bmp085InitDone = false; static bool bmp085InitDone = false;
static uint16_t bmp085_ut; // static result of temperature measurement static uint16_t bmp085_ut; // static result of temperature measurement
@ -258,7 +253,8 @@ static void bmp085_get_up(void)
convOverrun++; convOverrun++;
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data); i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
bmp085_up = (((uint32_t)data[0] << 16) | ((uint32_t)data[1] << 8) | (uint32_t)data[2]) >> (8 - bmp085.oversampling_setting); bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2])
>> (8 - bmp085.oversampling_setting);
} }
static void bmp085_calculate(int32_t *pressure, int32_t *temperature) static void bmp085_calculate(int32_t *pressure, int32_t *temperature)

View file

@ -11,7 +11,6 @@
// SCL PB10 // SCL PB10
// SDA PB11 // SDA PB11
#ifdef SOFT_I2C #ifdef SOFT_I2C
#define SCL_H GPIOB->BSRR = Pin_10 /* GPIO_SetBits(GPIOB , GPIO_Pin_10) */ #define SCL_H GPIOB->BSRR = Pin_10 /* GPIO_SetBits(GPIOB , GPIO_Pin_10) */
@ -26,21 +25,24 @@
static void I2C_delay(void) static void I2C_delay(void)
{ {
volatile int i = 7; volatile int i = 7;
while (i) while (i) {
i--; i--;
} }
}
static bool I2C_Start(void) static bool I2C_Start(void)
{ {
SDA_H; SDA_H;
SCL_H; SCL_H;
I2C_delay(); I2C_delay();
if (!SDA_read) if (!SDA_read) {
return false; return false;
}
SDA_L; SDA_L;
I2C_delay(); I2C_delay();
if (SDA_read) if (SDA_read) {
return false; return false;
}
SDA_L; SDA_L;
I2C_delay(); I2C_delay();
return true; return true;
@ -104,10 +106,11 @@ static void I2C_SendByte(uint8_t byte)
while (i--) { while (i--) {
SCL_L; SCL_L;
I2C_delay(); I2C_delay();
if (byte & 0x80) if (byte & 0x80) {
SDA_H; SDA_H;
else } else {
SDA_L; SDA_L;
}
byte <<= 1; byte <<= 1;
I2C_delay(); I2C_delay();
SCL_H; SCL_H;
@ -149,8 +152,9 @@ void i2cInit(I2C_TypeDef * I2C)
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)
{ {
int i; int i;
if (!I2C_Start()) if (!I2C_Start()) {
return false; return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) { if (!I2C_WaitAck()) {
I2C_Stop(); I2C_Stop();
@ -171,8 +175,9 @@ bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data) bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data)
{ {
if (!I2C_Start()) if (!I2C_Start()) {
return false; return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) { if (!I2C_WaitAck()) {
I2C_Stop(); I2C_Stop();
@ -188,8 +193,9 @@ bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data)
bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf) bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
{ {
if (!I2C_Start()) if (!I2C_Start()) {
return false; return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) { if (!I2C_WaitAck()) {
I2C_Stop(); I2C_Stop();
@ -202,10 +208,11 @@ bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
I2C_WaitAck(); I2C_WaitAck();
while (len) { while (len) {
*buf = I2C_ReceiveByte(); *buf = I2C_ReceiveByte();
if (len == 1) if (len == 1) {
I2C_NoAck(); I2C_NoAck();
else } else {
I2C_Ack(); I2C_Ack();
}
buf++; buf++;
len--; len--;
} }

View file

@ -60,11 +60,12 @@ static void i2c_er_handler(void)
volatile uint32_t SR1Register; volatile uint32_t SR1Register;
// Read the I2C1 status register // Read the I2C1 status register
SR1Register = I2Cx->SR1; SR1Register = I2Cx->SR1;
if (SR1Register & 0x0F00) { //an error if (SR1Register & 0x0F00) {
error = true; error = true;
// I2C1error.error = ((SR1Register & 0x0F00) >> 8); // save error // I2C1error.error = ((SR1Register & 0x0F00) >> 8); // save error
// I2C1error.job = job; // the task // I2C1error.job = job; // the task
} }
// If AF, BERR or ARLO, abandon the current job and commence new if there are jobs // If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
if (SR1Register & 0x0700) { 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) (void) I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
@ -101,7 +102,7 @@ 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); // wait for any stop to finish sending
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
@ -139,7 +140,7 @@ 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); // wait for any stop to finish sending
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
@ -194,7 +195,8 @@ void i2c_ev_handler(void)
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 //receiving greater than three bytes, sending subaddress, or transmitting else
//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
@ -204,7 +206,7 @@ void i2c_ev_handler(void)
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
read_p[index++] = I2C_ReceiveData(I2Cx); // read data N-2 read_p[index++] = I2C_ReceiveData(I2Cx); // 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++] = I2C_ReceiveData(I2Cx); // read data N-1 read_p[index++] = I2C_ReceiveData(I2Cx); // 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
@ -229,7 +231,7 @@ void i2c_ev_handler(void)
} }
} }
//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++] = I2C_ReceiveData(I2Cx); read_p[index++] = I2C_ReceiveData(I2Cx);
if (bytes == (index + 3)) if (bytes == (index + 3))
@ -301,7 +303,6 @@ void i2cInit(I2C_TypeDef *I2C)
NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQn; NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_Init(&NVIC_InitStructure); NVIC_Init(&NVIC_InitStructure);
} }
uint16_t i2cGetErrorCounter(void) uint16_t i2cGetErrorCounter(void)

View file

@ -15,7 +15,6 @@
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000) #define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT)) #define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C1_SCL_GPIO GPIOB #define I2C1_SCL_GPIO GPIOB
#define I2C1_SCL_PIN GPIO_Pin_6 #define I2C1_SCL_PIN GPIO_Pin_6
#define I2C1_SCL_PIN_SOURCE GPIO_PinSource6 #define I2C1_SCL_PIN_SOURCE GPIO_PinSource6
@ -45,12 +44,9 @@ static volatile uint16_t i2c2ErrorCount = 0;
uint32_t i2cTimeoutUserCallback(I2C_TypeDef *I2Cx) uint32_t i2cTimeoutUserCallback(I2C_TypeDef *I2Cx)
{ {
if (I2Cx == I2C1) if (I2Cx == I2C1) {
{
i2c1ErrorCount++; i2c1ErrorCount++;
} } else {
else
{
i2c2ErrorCount++; i2c2ErrorCount++;
} }
return false; return false;
@ -61,10 +57,7 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
GPIO_InitTypeDef GPIO_InitStructure; GPIO_InitTypeDef GPIO_InitStructure;
I2C_InitTypeDef I2C_InitStructure; I2C_InitTypeDef I2C_InitStructure;
/////////////////////////////////// if (I2Cx == I2C1) {
if (I2Cx == I2C1)
{
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE); RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE); RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
RCC_AHBPeriphClockCmd(I2C1_SCL_CLK_SOURCE | I2C1_SDA_CLK_SOURCE, ENABLE); RCC_AHBPeriphClockCmd(I2C1_SCL_CLK_SOURCE | I2C1_SDA_CLK_SOURCE, ENABLE);
@ -107,10 +100,7 @@ void i2cInitPort(I2C_TypeDef *I2Cx)
I2C_Cmd(I2C1, ENABLE); I2C_Cmd(I2C1, ENABLE);
} }
/////////////////////////////////// if (I2Cx == I2C2) {
if (I2Cx == I2C2)
{
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE); RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE); RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
RCC_AHBPeriphClockCmd(I2C2_SCL_CLK_SOURCE | I2C2_SDA_CLK_SOURCE, ENABLE); RCC_AHBPeriphClockCmd(I2C2_SCL_CLK_SOURCE | I2C2_SDA_CLK_SOURCE, ENABLE);
@ -160,7 +150,6 @@ void i2cInit(I2C_TypeDef *I2C)
uint16_t i2cGetErrorCounter(void) uint16_t i2cGetErrorCounter(void)
{ {
// FIXME implement
return i2c1ErrorCount; return i2c1ErrorCount;
} }
@ -170,22 +159,22 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
/* Test on BUSY Flag */ /* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0)
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */ /* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write); I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
/* Wait until TXIS flag is set */ /* Wait until TXIS flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0)
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
/* Send Register address */ /* Send Register address */
I2C_SendData(I2Cx, (uint8_t) reg); I2C_SendData(I2Cx, (uint8_t) reg);
@ -194,19 +183,20 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
{ {
if((i2cTimeout--) == 0) if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */ /* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop); I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
/* Wait until TXIS flag is set */ /* Wait until TXIS flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0) return return i2cTimeoutUserCallback(I2Cx);
i2cTimeoutUserCallback(I2Cx); }
} }
/* Write data to TXDR */ /* Write data to TXDR */
@ -214,9 +204,10 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
/* Wait until STOPF flag is set */ /* Wait until STOPF flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0) return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
}
} }
/* Clear STOPF flag */ /* Clear STOPF flag */
@ -230,50 +221,50 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
I2C_TypeDef* I2Cx = I2C1; I2C_TypeDef* I2Cx = I2C1;
/* Test on BUSY Flag */ /* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0)
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */ /* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write); I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
/* Wait until TXIS flag is set */ /* Wait until TXIS flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0)
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
if(len > 1) if (len > 1) {
reg |= 0x80; reg |= 0x80;
}
/* Send Register address */ /* Send Register address */
I2C_SendData(I2Cx, (uint8_t) reg); I2C_SendData(I2Cx, (uint8_t) reg);
/* Wait until TC flag is set */ /* Wait until TC flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0)
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */ /* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read); I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
/* Wait until all data are received */ /* Wait until all data are received */
while (len) while (len) {
{
/* Wait until RXNE flag is set */ /* Wait until RXNE flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0)
return i2cTimeoutUserCallback(I2Cx); return i2cTimeoutUserCallback(I2Cx);
} }
}
/* Read data from RXDR */ /* Read data from RXDR */
*buf = I2C_ReceiveData(I2Cx); *buf = I2C_ReceiveData(I2Cx);
@ -286,10 +277,10 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
/* Wait until STOPF flag is set */ /* Wait until STOPF flag is set */
i2cTimeout = I2C_LONG_TIMEOUT; i2cTimeout = I2C_LONG_TIMEOUT;
while(I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
{ if ((i2cTimeout--) == 0) {
if((i2cTimeout--) == 0) return return i2cTimeoutUserCallback(I2Cx);
i2cTimeoutUserCallback(I2Cx); }
} }
/* Clear STOPF flag */ /* Clear STOPF flag */

View file

@ -1,4 +1,3 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
@ -36,7 +35,6 @@ static pwmInputPort_t pwmInputPorts[MAX_PWM_INPUT_PORTS];
static uint16_t captures[MAX_PWM_INPUT_PORTS]; static uint16_t captures[MAX_PWM_INPUT_PORTS];
static void ppmCallback(uint8_t port, captureCompare_t capture) static void ppmCallback(uint8_t port, captureCompare_t capture)
{ {
int32_t diff; int32_t diff;

View file

@ -1,4 +1,3 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>

View file

@ -1,6 +1,5 @@
#pragma once #pragma once
typedef enum { typedef enum {
SERIAL_NOT_INVERTED = 0, SERIAL_NOT_INVERTED = 0,
SERIAL_INVERTED SERIAL_INVERTED