1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

Converted I2C, EXTI and SONAR to new IO (#389)

* Converted I2C to new IO
* Converted SONAR to new IO
* Converted EXTI to new IO
* Whitespace and target.h cleanup
* Catch up with betaflight changes
* Got ALIENFLIGHTF1 and CC3D_NRF24_OPBL targets to fit in ROM
* Target fixup
* Fixed build errors in targets
* Fixed CC3D and NAZE targets.
This commit is contained in:
Martin Budden 2016-07-31 10:25:03 +01:00 committed by Konstantin Sharlaimov
parent 8f8a29e97f
commit 0489eb8b08
82 changed files with 1891 additions and 1821 deletions

View file

@ -375,6 +375,7 @@ COMMON_SRC = \
drivers/bus_i2c_soft.c \
drivers/bus_spi.c \
drivers/bus_spi_soft.c \
drivers/exti.c \
drivers/gps_i2cnav.c \
drivers/gyro_sync.c \
drivers/io.c \
@ -476,7 +477,8 @@ VCP_SRC = \
vcp/usb_istr.c \
vcp/usb_prop.c \
vcp/usb_pwr.c \
drivers/serial_usb_vcp.c
drivers/serial_usb_vcp.c \
drivers/usb_io.c
endif
STM32F10x_COMMON_SRC = \

View file

@ -17,6 +17,10 @@
#pragma once
#ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE
#endif
typedef struct gyro_s {
sensorGyroInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function

View file

@ -66,7 +66,7 @@ bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(ADXL345_ADDRESS, 0x00, 1, &sig);
ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
if (!ack || sig != 0xE5)
return false;
@ -82,14 +82,14 @@ static void adxl345Init(acc_t *acc)
{
if (useFifo) {
uint8_t fifoDepth = 16;
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400);
i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM);
} else {
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100);
}
acc->acc_1G = 256; // 3.3V operation
}
@ -110,7 +110,7 @@ static bool adxl345Read(int16_t *accelData)
do {
i++;
if (!i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf)) {
return false;
}
@ -125,7 +125,7 @@ static bool adxl345Read(int16_t *accelData)
acc_samples = i;
} else {
if (!i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf)) {
return false;
}

View file

@ -40,7 +40,7 @@ bool bma280Detect(acc_t *acc)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(BMA280_ADDRESS, 0x00, 1, &sig);
ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
if (!ack || sig != 0xFB)
return false;
@ -51,8 +51,8 @@ bool bma280Detect(acc_t *acc)
static void bma280Init(acc_t *acc)
{
i2cWrite(BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
i2cWrite(BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW
acc->acc_1G = 512 * 8;
}
@ -61,7 +61,7 @@ static bool bma280Read(int16_t *accelData)
{
uint8_t buf[6];
if (!i2cRead(BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) {
return false;
}

View file

@ -63,7 +63,7 @@ bool l3g4200dDetect(gyro_t *gyro)
delay(25);
i2cRead(L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
if (deviceid != L3G4200D_ID)
return false;
@ -82,7 +82,6 @@ static void l3g4200dInit(uint8_t lpf)
uint8_t mpuLowPassFilter = L3G4200D_DLPF_32HZ;
// Conversion from MPU6XXX LPF values
switch (lpf) {
default:
case 3: // BITS_DLPF_CFG_42HZ
@ -101,12 +100,12 @@ static void l3g4200dInit(uint8_t lpf)
delay(100);
ack = i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS);
ack = i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS);
if (!ack)
failureMode(FAILURE_ACC_INIT);
delay(5);
i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter);
i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter);
}
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
@ -114,7 +113,7 @@ static bool l3g4200dRead(int16_t *gyroADC)
{
uint8_t buf[6];
if (!i2cRead(L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) {
return false;
}

View file

@ -19,14 +19,16 @@
#include <stdint.h>
#include "platform.h"
#include "build_config.h"
#ifdef USE_ACC_LSM303DLHC
#include "debug.h"
#include "common/maths.h"
#include "common/axis.h"
#include "system.h"
#include "gpio.h"
#include "io.h"
#include "bus_i2c.h"
#include "sensor.h"
@ -115,15 +117,15 @@ int32_t accelSummedSamples500Hz[3];
void lsm303dlhcAccInit(acc_t *acc)
{
i2cWrite(LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
delay(100);
i2cWrite(LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
delay(10);
i2cWrite(LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G);
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G);
delay(100);
@ -135,7 +137,7 @@ static bool lsm303dlhcAccRead(int16_t *gyroADC)
{
uint8_t buf[6];
bool ack = i2cRead(LSM303DLHC_ACCEL_ADDRESS, AUTO_INCREMENT_ENABLE | OUT_X_L_A, 6, buf);
bool ack = i2cRead(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, AUTO_INCREMENT_ENABLE | OUT_X_L_A, 6, buf);
if (!ack) {
return false;
@ -160,7 +162,7 @@ bool lsm303dlhcAccDetect(acc_t *acc)
bool ack;
uint8_t status;
ack = i2cRead(LSM303DLHC_ACCEL_ADDRESS, LSM303DLHC_STATUS_REG_A, 1, &status);
ack = i2cRead(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, LSM303DLHC_STATUS_REG_A, 1, &status);
if (!ack)
return false;
@ -168,4 +170,5 @@ bool lsm303dlhcAccDetect(acc_t *acc)
acc->read = lsm303dlhcAccRead;
return true;
}
#endif

View file

@ -22,8 +22,7 @@
*/
/* LSM303DLHC ACC struct */
typedef struct
{
typedef struct {
uint8_t Power_Mode; /* Power-down/Normal Mode */
uint8_t AccOutput_DataRate; /* OUT data rate */
uint8_t Axes_Enable; /* Axes enable */
@ -31,25 +30,23 @@ typedef struct
uint8_t BlockData_Update; /* Block Data Update */
uint8_t Endianness; /* Endian Data selection */
uint8_t AccFull_Scale; /* Full Scale selection */
}LSM303DLHCAcc_InitTypeDef;
} LSM303DLHCAcc_InitTypeDef;
/* LSM303DLHC Acc High Pass Filter struct */
typedef struct
{
typedef struct {
uint8_t HighPassFilter_Mode_Selection; /* Internal filter mode */
uint8_t HighPassFilter_CutOff_Frequency; /* High pass filter cut-off frequency */
uint8_t HighPassFilter_AOI1; /* HPF_enabling/disabling for AOI function on interrupt 1 */
uint8_t HighPassFilter_AOI2; /* HPF_enabling/disabling for AOI function on interrupt 2 */
}LSM303DLHCAcc_FilterConfigTypeDef;
} LSM303DLHCAcc_FilterConfigTypeDef;
/* LSM303DLHC Mag struct */
typedef struct
{
typedef struct {
uint8_t Temperature_Sensor; /* Temperature sensor enable/disable */
uint8_t MagOutput_DataRate; /* OUT data rate */
uint8_t Working_Mode; /* operating mode */
uint8_t MagFull_Scale; /* Full Scale selection */
}LSM303DLHCMag_InitTypeDef;
} LSM303DLHCMag_InitTypeDef;
/**
* @}
*/

View file

@ -28,6 +28,10 @@
#include "accgyro.h"
#include "accgyro_mma845x.h"
#ifndef MMA8452_I2C_INSTANCE
#define MMA8452_I2C_INSTANCE I2CDEV_1
#endif
// MMA8452QT, Standard address 0x1C
// ACC_INT2 routed to PA5
@ -85,7 +89,7 @@ bool mma8452Detect(acc_t *acc)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
return false;
@ -101,33 +105,26 @@ static inline void mma8451ConfigureInterrupt(void)
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
gpio_config_t gpio;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
gpio.pin = Pin_5;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOA, &gpio);
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU, RESOURCE_EXTI, 0);
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
#endif
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
}
static void mma8452Init(acc_t *acc)
{
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG1, 0); // Put device in standby to configure stuff
i2cWrite(MMA8452_ADDRESS, MMA8452_XYZ_DATA_CFG, MMA8452_FS_RANGE_8G);
i2cWrite(MMA8452_ADDRESS, MMA8452_HP_FILTER_CUTOFF, MMA8452_HPF_CUTOFF_LV4);
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG2, MMA8452_CTRL_REG2_MODS_HR | MMA8452_CTRL_REG2_MODS_HR << 3); // High resolution measurement in both sleep and active modes
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG1, 0); // Put device in standby to configure stuff
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_XYZ_DATA_CFG, MMA8452_FS_RANGE_8G);
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_HP_FILTER_CUTOFF, MMA8452_HPF_CUTOFF_LV4);
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG2, MMA8452_CTRL_REG2_MODS_HR | MMA8452_CTRL_REG2_MODS_HR << 3); // High resolution measurement in both sleep and active modes
mma8451ConfigureInterrupt();
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG1, MMA8452_CTRL_REG1_LNOISE | MMA8452_CTRL_REG1_ACTIVE); // Turn on measurements, low noise at max scale mode, Data Rate 800Hz. LNoise mode makes range +-4G.
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG1, MMA8452_CTRL_REG1_LNOISE | MMA8452_CTRL_REG1_ACTIVE); // Turn on measurements, low noise at max scale mode, Data Rate 800Hz. LNoise mode makes range +-4G.
acc->acc_1G = 256;
}
@ -136,7 +133,7 @@ static bool mma8452Read(int16_t *accelData)
{
uint8_t buf[6];
if (!i2cRead(MMA8452_ADDRESS, MMA8452_OUT_X_MSB, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_OUT_X_MSB, 6, buf)) {
return false;
}

View file

@ -32,7 +32,6 @@
#include "gpio.h"
#include "exti.h"
#include "bus_i2c.h"
#include "gyro_sync.h"
#include "sensor.h"
#include "accgyro.h"
@ -56,6 +55,10 @@ static volatile bool mpuDataReady;
static bool detectSPISensorsAndUpdateDetectionResult(void);
#endif
#ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE
#endif
mpuDetectionResult_t mpuDetectionResult;
mpuConfiguration_t mpuConfiguration;
@ -83,7 +86,12 @@ mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse)
// MPU datasheet specifies 30ms.
delay(35);
#ifndef USE_I2C
ack = false;
sig = 0;
#else
ack = mpuReadRegisterI2C(MPU_RA_WHO_AM_I, 1, &sig);
#endif
if (ack) {
mpuConfiguration.read = mpuReadRegisterI2C;
mpuConfiguration.write = mpuWriteRegisterI2C;
@ -169,6 +177,8 @@ static void mpu6050FindRevision(void)
mpuDetectionResult.resolution = MPU_HALF_RESOLUTION;
} else if (revision == 2) {
mpuDetectionResult.resolution = MPU_FULL_RESOLUTION;
} else if ((revision == 3) || (revision == 7)) {
mpuDetectionResult.resolution = MPU_FULL_RESOLUTION;
} else {
failureMode(FAILURE_ACC_INCOMPATIBLE);
}
@ -185,120 +195,61 @@ static void mpu6050FindRevision(void)
}
}
void MPU_DATA_READY_EXTI_Handler(void)
extiCallbackRec_t mpuIntCallbackRec;
void mpuIntExtiHandler(extiCallbackRec_t *cb)
{
if (EXTI_GetITStatus(mpuIntExtiConfig->exti_line) == RESET) {
return;
}
EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line);
UNUSED(cb);
mpuDataReady = true;
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
// Measure the delta in micro seconds between calls to the interrupt handler
static uint32_t lastCalledAt = 0;
static int32_t callDelta = 0;
uint32_t now = micros();
callDelta = now - lastCalledAt;
UNUSED(callDelta);
uint32_t callDelta = now - lastCalledAt;
debug[0] = callDelta;
lastCalledAt = now;
#endif
}
void configureMPUDataReadyInterruptHandling(void)
{
#ifdef USE_MPU_DATA_READY_SIGNAL
#ifdef STM32F10X
// enable AFIO for EXTI support
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
#ifdef STM32F303xC
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
#ifdef STM32F10X
gpioExtiLineConfig(mpuIntExtiConfig->exti_port_source, mpuIntExtiConfig->exti_pin_source);
#endif
#ifdef STM32F303xC
gpioExtiLineConfig(mpuIntExtiConfig->exti_port_source, mpuIntExtiConfig->exti_pin_source);
#endif
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = GPIO_ReadInputDataBit(mpuIntExtiConfig->gpioPort, mpuIntExtiConfig->gpioPin);
if (status) {
return;
}
#endif
registerExtiCallbackHandler(mpuIntExtiConfig->exti_irqn, MPU_DATA_READY_EXTI_Handler);
EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line);
EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = mpuIntExtiConfig->exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = mpuIntExtiConfig->exti_irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MPU_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MPU_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif
}
void mpuIntExtiInit(void)
{
gpio_config_t gpio;
static bool mpuExtiInitDone = false;
if (mpuExtiInitDone || !mpuIntExtiConfig) {
return;
}
#ifdef STM32F303
if (mpuIntExtiConfig->gpioAHBPeripherals) {
RCC_AHBPeriphClockCmd(mpuIntExtiConfig->gpioAHBPeripherals, ENABLE);
}
#endif
#ifdef STM32F10X
if (mpuIntExtiConfig->gpioAPB2Peripherals) {
RCC_APB2PeriphClockCmd(mpuIntExtiConfig->gpioAPB2Peripherals, ENABLE);
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag);
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = IORead(mpuIntIO);
if (status) {
return;
}
#endif
gpio.pin = mpuIntExtiConfig->gpioPin;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(mpuIntExtiConfig->gpioPort, &gpio);
IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 0);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
configureMPUDataReadyInterruptHandling();
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(mpuIntIO, true);
#endif
mpuExtiInitDone = true;
}
static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data)
{
bool ack = i2cRead(MPU_ADDRESS, reg, length, data);
bool ack = i2cRead(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, length, data);
return ack;
}
static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data)
{
bool ack = i2cWrite(MPU_ADDRESS, reg, data);
bool ack = i2cWrite(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, data);
return ack;
}
@ -334,11 +285,14 @@ bool mpuGyroRead(int16_t *gyroADC)
return true;
}
void checkMPUDataReady(bool *mpuDataReadyPtr) {
bool checkMPUDataReady(void)
{
bool ret;
if (mpuDataReady) {
*mpuDataReadyPtr = true;
ret = true;
mpuDataReady= false;
} else {
*mpuDataReadyPtr = false;
ret = false;
}
return ret;
}

View file

@ -17,6 +17,8 @@
#pragma once
#include "exti.h"
// MPU6050
#define MPU_RA_WHO_AM_I 0x75
#define MPU_RA_WHO_AM_I_LEGACY 0x00
@ -117,26 +119,19 @@
typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data);
typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data);
typedef void(*mpuResetFuncPtr)(void);
typedef struct mpuConfiguration_s {
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
mpuReadRegisterFunc read;
mpuWriteRegisterFunc write;
mpuReadRegisterFunc slowread;
mpuWriteRegisterFunc verifywrite;
mpuResetFuncPtr reset;
} mpuConfiguration_t;
extern mpuConfiguration_t mpuConfiguration;
enum lpf_e {
INV_FILTER_256HZ_NOLPF2 = 0,
INV_FILTER_188HZ,
INV_FILTER_98HZ,
INV_FILTER_42HZ,
INV_FILTER_20HZ,
INV_FILTER_10HZ,
INV_FILTER_5HZ,
INV_FILTER_2100HZ_NOLPF,
NUM_FILTER
};
enum gyro_fsr_e {
INV_FSR_250DPS = 0,
INV_FSR_500DPS,
@ -144,11 +139,19 @@ enum gyro_fsr_e {
INV_FSR_2000DPS,
NUM_GYRO_FSR
};
enum fchoice_b {
FCB_DISABLED = 0,
FCB_8800_32,
FCB_3600_32
};
enum clock_sel_e {
INV_CLK_INTERNAL = 0,
INV_CLK_PLL,
NUM_CLK
};
enum accel_fsr_e {
INV_FSR_2G = 0,
INV_FSR_4G,
@ -163,7 +166,8 @@ typedef enum {
MPU_60x0,
MPU_60x0_SPI,
MPU_65xx_I2C,
MPU_65xx_SPI
MPU_65xx_SPI,
MPU_9250_SPI
} detectedMPUSensor_e;
typedef enum {
@ -183,4 +187,4 @@ void mpuIntExtiInit(void);
bool mpuAccRead(int16_t *accData);
bool mpuGyroRead(int16_t *gyroADC);
mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse);
void checkMPUDataReady(bool *mpuDataReadyPtr);
bool checkMPUDataReady(void);

View file

@ -30,7 +30,6 @@
#include "accgyro.h"
#include "accgyro_mpu.h"
#include "accgyro_mpu3050.h"
#include "gyro_sync.h"
// MPU3050, Standard address 0x68
#define MPU3050_ADDRESS 0x68

View file

@ -38,8 +38,6 @@
#include "accgyro_mpu.h"
#include "accgyro_mpu6050.h"
extern uint8_t mpuLowPassFilter;
//#define DEBUG_MPU_DATA_READY_INTERRUPT
// MPU6050, Standard address 0x68

View file

@ -12,6 +12,9 @@
#define MPU6000_WHO_AM_I_CONST (0x68)
// RF = Register Flag
#define MPU_RF_DATA_RDY_EN (1 << 0)
bool mpu6000SpiDetect(void);
bool mpu6000SpiAccDetect(acc_t *acc);

View file

@ -29,3 +29,7 @@ typedef struct baro_s {
baroOpFuncPtr get_up;
baroCalculateFuncPtr calculate;
} baro_t;
#ifndef BARO_I2C_INSTANCE
#define BARO_I2C_INSTANCE I2C_DEVICE
#endif

View file

@ -28,24 +28,29 @@
#include "system.h"
#include "bus_i2c.h"
#include "nvic.h"
#include "exti.h"
#include "io.h"
#include "barometer_bmp085.h"
#ifdef BARO
#if defined(BARO_EOC_GPIO)
static IO_t eocIO;
static bool isConversionComplete = false;
static bool isEOCConnected = true;
// EXTI14 for BMP085 End of Conversion Interrupt
void BMP085_EOC_EXTI_Handler(void) {
if (EXTI_GetITStatus(EXTI_Line14) == SET) {
EXTI_ClearITPendingBit(EXTI_Line14);
void bmp085_extiHandler(extiCallbackRec_t* cb)
{
UNUSED(cb);
isConversionComplete = true;
}
}
#endif
bool bmp085TestEOCConnected(const bmp085Config_t *config);
# endif
typedef struct {
int16_t ac1;
@ -123,28 +128,29 @@ static int32_t bmp085_get_temperature(uint32_t ut);
static int32_t bmp085_get_pressure(uint32_t up);
STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature);
static IO_t xclrIO;
#ifdef BARO_XCLR_PIN
#define BMP085_OFF digitalLo(BARO_XCLR_GPIO, BARO_XCLR_PIN);
#define BMP085_ON digitalHi(BARO_XCLR_GPIO, BARO_XCLR_PIN);
#define BMP085_OFF IOLo(xclrIO);
#define BMP085_ON IOHi(xclrIO);
#else
#define BMP085_OFF
#define BMP085_ON
#endif
void bmp085InitXCLRGpio(const bmp085Config_t *config) {
gpio_config_t gpio;
RCC_APB2PeriphClockCmd(config->gpioAPB2Peripherals, ENABLE);
gpio.pin = config->xclrGpioPin;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_Out_PP;
gpioInit(config->xclrGpioPort, &gpio);
void bmp085InitXclrIO(const bmp085Config_t *config)
{
if (!xclrIO && config && config->xclrIO) {
xclrIO = IOGetByTag(config->xclrIO);
IOInit(xclrIO, OWNER_BARO, RESOURCE_OUTPUT, 0);
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
}
}
void bmp085Disable(const bmp085Config_t *config)
{
bmp085InitXCLRGpio(config);
bmp085InitXclrIO(config);
BMP085_OFF;
}
@ -152,53 +158,39 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
{
uint8_t data;
bool ack;
#if defined(BARO_EOC_GPIO)
IO_t eocIO = IO_NONE;
#endif
if (bmp085InitDone)
return true;
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
if (config) {
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
gpio_config_t gpio;
bmp085InitXCLRGpio(config);
gpio.pin = config->eocGpioPin;
gpio.mode = Mode_IPD;
gpioInit(config->eocGpioPort, &gpio);
BMP085_ON;
registerExtiCallbackHandler(EXTI15_10_IRQn, BMP085_EOC_EXTI_Handler);
bmp085InitXclrIO(config);
BMP085_ON; // enable baro
#if defined(BARO_EOC_GPIO) && defined(USE_EXTI)
if (config && config->eocIO) {
eocIO = IOGetByTag(config->eocIO);
// EXTI interrupt for barometer EOC
gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14);
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
// Enable and set EXTI10-15 Interrupt to the lowest priority
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BARO_EXT);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BARO_EXT);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
IOInit(eocIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
IOConfigGPIO(eocIO, Mode_IN_FLOATING);
EXTIHandlerInit(&bmp085_extiCallbackRec, bmp085_extiHandler);
EXTIConfig(eocIO, &bmp085_extiCallbackRec, NVIC_PRIO_BARO_EXTI, EXTI_Trigger_Rising);
EXTIEnable(eocIO, true);
}
#else
UNUSED(config);
#endif
delay(200); // datasheet says 10ms, we'll be careful and do 200.
delay(20); // datasheet says 10ms, we'll be careful and do 20.
ack = i2cRead(BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
if (ack) {
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
bmp085.oversampling_setting = 3;
if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */
i2cRead(BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */
bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */
bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */
bmp085_get_cal_param(); /* readout bmp085 calibparam structure */
@ -218,13 +210,8 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
}
#if defined(BARO_EOC_GPIO)
EXTI_InitTypeDef EXTI_InitStructure;
EXTI_StructInit(&EXTI_InitStructure);
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
EXTI_InitStructure.EXTI_LineCmd = DISABLE;
EXTI_Init(&EXTI_InitStructure);
unregisterExtiCallbackHandler(EXTI15_10_IRQn, BMP085_EOC_EXTI_Handler);
if (eocIO)
EXTIRelease(eocIO);
#endif
BMP085_OFF;
@ -290,7 +277,7 @@ static void bmp085_start_ut(void)
#if defined(BARO_EOC_GPIO)
isConversionComplete = false;
#endif
i2cWrite(BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
}
static void bmp085_get_ut(void)
@ -304,7 +291,7 @@ static void bmp085_get_ut(void)
}
#endif
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
bmp085_ut = (data[0] << 8) | data[1];
}
@ -318,7 +305,7 @@ static void bmp085_start_up(void)
isConversionComplete = false;
#endif
i2cWrite(BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
}
/** read out up for pressure conversion
@ -336,7 +323,7 @@ static void bmp085_get_up(void)
}
#endif
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
i2cRead(BARO_I2C_INSTANCE, 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);
}
@ -356,7 +343,7 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature
static void bmp085_get_cal_param(void)
{
uint8_t data[22];
i2cRead(BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
/*parameters AC1-AC6*/
bmp085.cal_param.ac1 = (data[0] << 8) | data[1];
@ -379,12 +366,14 @@ static void bmp085_get_cal_param(void)
#if defined(BARO_EOC_GPIO)
bool bmp085TestEOCConnected(const bmp085Config_t *config)
{
if (!bmp085InitDone) {
UNUSED(config);
if (!bmp085InitDone && eocIO) {
bmp085_start_ut();
delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure
// conversion should have finished now so check if EOC is high
uint8_t status = GPIO_ReadInputDataBit(config->eocGpioPort, config->eocGpioPin);
uint8_t status = IORead(eocIO);
if (status) {
return true;
}

View file

@ -18,11 +18,8 @@
#pragma once
typedef struct bmp085Config_s {
uint32_t gpioAPB2Peripherals;
uint16_t xclrGpioPin;
GPIO_TypeDef *xclrGpioPort;
uint16_t eocGpioPin;
GPIO_TypeDef *eocGpioPort;
ioTag_t xclrIO;
ioTag_t eocIO;
} bmp085Config_t;
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);

View file

@ -28,50 +28,12 @@
#include "bus_i2c.h"
#include "barometer_bmp280.h"
#include "barometer_spi_bmp280.h"
#ifdef BARO
// BMP280, address 0x76
#define BMP280_I2C_ADDR (0x76)
#define BMP280_DEFAULT_CHIP_ID (0x58)
#define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */
#define BMP280_RST_REG (0xE0) /* Softreset Register */
#define BMP280_STAT_REG (0xF3) /* Status Register */
#define BMP280_CTRL_MEAS_REG (0xF4) /* Ctrl Measure Register */
#define BMP280_CONFIG_REG (0xF5) /* Configuration Register */
#define BMP280_PRESSURE_MSB_REG (0xF7) /* Pressure MSB Register */
#define BMP280_PRESSURE_LSB_REG (0xF8) /* Pressure LSB Register */
#define BMP280_PRESSURE_XLSB_REG (0xF9) /* Pressure XLSB Register */
#define BMP280_TEMPERATURE_MSB_REG (0xFA) /* Temperature MSB Reg */
#define BMP280_TEMPERATURE_LSB_REG (0xFB) /* Temperature LSB Reg */
#define BMP280_TEMPERATURE_XLSB_REG (0xFC) /* Temperature XLSB Reg */
#define BMP280_FORCED_MODE (0x01)
#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG (0x88)
#define BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH (24)
#define BMP280_DATA_FRAME_SIZE (6)
#define BMP280_OVERSAMP_SKIPPED (0x00)
#define BMP280_OVERSAMP_1X (0x01)
#define BMP280_OVERSAMP_2X (0x02)
#define BMP280_OVERSAMP_4X (0x03)
#define BMP280_OVERSAMP_8X (0x04)
#define BMP280_OVERSAMP_16X (0x05)
// configure pressure and temperature oversampling, forced sampling mode
#define BMP280_PRESSURE_OSR (BMP280_OVERSAMP_8X)
#define BMP280_TEMPERATURE_OSR (BMP280_OVERSAMP_1X)
#define BMP280_MODE (BMP280_PRESSURE_OSR << 2 | BMP280_TEMPERATURE_OSR << 5 | BMP280_FORCED_MODE)
#define T_INIT_MAX (20)
// 20/16 = 1.25 ms
#define T_MEASURE_PER_OSRS_MAX (37)
// 37/16 = 2.3125 ms
#define T_SETUP_PRESSURE_MAX (10)
// 10/16 = 0.625 ms
typedef struct bmp280_calib_param_s {
uint16_t dig_T1; /* calibration T1 data */
int16_t dig_T2; /* calibration T2 data */
@ -92,13 +54,15 @@ static uint8_t bmp280_chip_id = 0;
static bool bmp280InitDone = false;
STATIC_UNIT_TESTED bmp280_calib_param_t bmp280_cal;
// uncompensated pressure and temperature
STATIC_UNIT_TESTED int32_t bmp280_up = 0;
STATIC_UNIT_TESTED int32_t bmp280_ut = 0;
int32_t bmp280_up = 0;
int32_t bmp280_ut = 0;
static void bmp280_start_ut(void);
static void bmp280_get_ut(void);
#ifndef USE_BARO_SPI_BMP280
static void bmp280_start_up(void);
static void bmp280_get_up(void);
#endif
STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature);
bool bmp280Detect(baro_t *baro)
@ -108,14 +72,26 @@ bool bmp280Detect(baro_t *baro)
delay(20);
i2cRead(BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
#ifdef USE_BARO_SPI_BMP280
bmp280SpiInit();
bmp280ReadRegister(BMP280_CHIP_ID_REG, 1, &bmp280_chip_id);
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
return false;
// read calibration
i2cRead(BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
bmp280ReadRegister(BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
// set oversampling + power mode (forced), and start sampling
i2cWrite(BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
#else
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
return false;
// read calibration
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
// set oversampling + power mode (forced), and start sampling
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
#endif
bmp280InitDone = true;
@ -126,8 +102,13 @@ bool bmp280Detect(baro_t *baro)
// only _up part is executed, and gets both temperature and pressure
baro->up_delay = ((T_INIT_MAX + T_MEASURE_PER_OSRS_MAX * (((1 << BMP280_TEMPERATURE_OSR) >> 1) + ((1 << BMP280_PRESSURE_OSR) >> 1)) + (BMP280_PRESSURE_OSR ? T_SETUP_PRESSURE_MAX : 0) + 15) / 16) * 1000;
#ifdef USE_BARO_SPI_BMP280
baro->start_up = bmp280_spi_start_up;
baro->get_up = bmp280_spi_get_up;
#else
baro->start_up = bmp280_start_up;
baro->get_up = bmp280_get_up;
#endif
baro->calculate = bmp280_calculate;
return true;
@ -143,11 +124,12 @@ static void bmp280_get_ut(void)
// dummy
}
#ifndef USE_BARO_SPI_BMP280
static void bmp280_start_up(void)
{
// start measurement
// set oversampling + power mode (forced), and start sampling
i2cWrite(BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
}
static void bmp280_get_up(void)
@ -155,10 +137,11 @@ static void bmp280_get_up(void)
uint8_t data[BMP280_DATA_FRAME_SIZE];
// read data from sensor
i2cRead(BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
}
#endif
// Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC
// t_fine carries fine temperature as global value

View file

@ -17,5 +17,44 @@
#pragma once
#define BMP280_I2C_ADDR (0x76)
#define BMP280_DEFAULT_CHIP_ID (0x58)
#define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */
#define BMP280_RST_REG (0xE0) /* Softreset Register */
#define BMP280_STAT_REG (0xF3) /* Status Register */
#define BMP280_CTRL_MEAS_REG (0xF4) /* Ctrl Measure Register */
#define BMP280_CONFIG_REG (0xF5) /* Configuration Register */
#define BMP280_PRESSURE_MSB_REG (0xF7) /* Pressure MSB Register */
#define BMP280_PRESSURE_LSB_REG (0xF8) /* Pressure LSB Register */
#define BMP280_PRESSURE_XLSB_REG (0xF9) /* Pressure XLSB Register */
#define BMP280_TEMPERATURE_MSB_REG (0xFA) /* Temperature MSB Reg */
#define BMP280_TEMPERATURE_LSB_REG (0xFB) /* Temperature LSB Reg */
#define BMP280_TEMPERATURE_XLSB_REG (0xFC) /* Temperature XLSB Reg */
#define BMP280_FORCED_MODE (0x01)
#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG (0x88)
#define BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH (24)
#define BMP280_DATA_FRAME_SIZE (6)
#define BMP280_OVERSAMP_SKIPPED (0x00)
#define BMP280_OVERSAMP_1X (0x01)
#define BMP280_OVERSAMP_2X (0x02)
#define BMP280_OVERSAMP_4X (0x03)
#define BMP280_OVERSAMP_8X (0x04)
#define BMP280_OVERSAMP_16X (0x05)
// configure pressure and temperature oversampling, forced sampling mode
#define BMP280_PRESSURE_OSR (BMP280_OVERSAMP_8X)
#define BMP280_TEMPERATURE_OSR (BMP280_OVERSAMP_1X)
#define BMP280_MODE (BMP280_PRESSURE_OSR << 2 | BMP280_TEMPERATURE_OSR << 5 | BMP280_FORCED_MODE)
#define T_INIT_MAX (20)
// 20/16 = 1.25 ms
#define T_MEASURE_PER_OSRS_MAX (37)
// 37/16 = 2.3125 ms
#define T_SETUP_PRESSURE_MAX (10)
// 10/16 = 0.625 ms
bool bmp280Detect(baro_t *baro);

View file

@ -67,7 +67,7 @@ bool ms5611Detect(baro_t *baro)
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
ack = i2cRead(MS5611_ADDR, CMD_PROM_RD, 1, &sig);
ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig);
if (!ack)
return false;
@ -93,14 +93,14 @@ bool ms5611Detect(baro_t *baro)
static void ms5611_reset(void)
{
i2cWrite(MS5611_ADDR, CMD_RESET, 1);
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1);
delayMicroseconds(2800);
}
static uint16_t ms5611_prom(int8_t coef_num)
{
uint8_t rxbuf[2] = { 0, 0 };
i2cRead(MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
return rxbuf[0] << 8 | rxbuf[1];
}
@ -137,13 +137,13 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom)
static uint32_t ms5611_read_adc(void)
{
uint8_t rxbuf[3];
i2cRead(MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2];
}
static void ms5611_start_ut(void)
{
i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
}
static void ms5611_get_ut(void)
@ -153,7 +153,7 @@ static void ms5611_get_ut(void)
static void ms5611_start_up(void)
{
i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
}
static void ms5611_get_up(void)

View file

@ -17,15 +17,53 @@
#pragma once
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
#include "drivers/io.h"
#include "drivers/rcc.h"
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID
#endif
typedef enum I2CDevice {
I2CDEV_1,
I2CINVALID = -1,
I2CDEV_1 = 0,
I2CDEV_2,
I2CDEV_MAX = I2CDEV_2,
I2CDEV_3,
I2CDEV_MAX = I2CDEV_3,
} I2CDevice;
void i2cInit(I2CDevice index);
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 i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf);
typedef struct i2cDevice_s {
I2C_TypeDef *dev;
ioTag_t scl;
ioTag_t sda;
rccPeriphTag_t rcc;
bool overClock;
#if !defined(STM32F303xC)
uint8_t ev_irq;
uint8_t er_irq;
#endif
} i2cDevice_t;
typedef struct i2cState_s {
volatile bool error;
volatile bool busy;
volatile uint8_t addr;
volatile uint8_t reg;
volatile uint8_t bytes;
volatile uint8_t writing;
volatile uint8_t reading;
volatile uint8_t* write_p;
volatile uint8_t* read_p;
} i2cState_t;
void i2cSetOverclock(uint8_t overClock);
void i2cInit(I2CDevice device);
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data);
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data);
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf);
uint16_t i2cGetErrorCounter(void);
void i2cSetOverclock(uint8_t OverClock);

View file

@ -21,42 +21,29 @@
#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)
@ -145,7 +132,8 @@ static void I2C_SendByte(uint8_t byte)
I2C_delay();
if (byte & 0x80) {
SDA_H;
} else {
}
else {
SDA_L;
}
byte <<= 1;
@ -176,20 +164,24 @@ static uint8_t I2C_ReceiveByte(void)
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)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
{
UNUSED(device);
int i;
if (!I2C_Start()) {
i2cErrorCount++;
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
@ -203,6 +195,7 @@ bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
I2C_SendByte(data[i]);
if (!I2C_WaitAck()) {
I2C_Stop();
i2cErrorCount++;
return false;
}
}
@ -210,14 +203,17 @@ bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
return true;
}
bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data)
bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data)
{
UNUSED(device);
if (!I2C_Start()) {
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
i2cErrorCount++;
return false;
}
I2C_SendByte(reg);
@ -228,14 +224,17 @@ bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data)
return true;
}
bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
bool i2cRead(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
{
UNUSED(device);
if (!I2C_Start()) {
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
i2cErrorCount++;
return false;
}
I2C_SendByte(reg);
@ -247,7 +246,8 @@ bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
*buf = I2C_ReceiveByte();
if (len == 1) {
I2C_NoAck();
} else {
}
else {
I2C_Ack();
}
buf++;
@ -259,8 +259,8 @@ bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
uint16_t i2cGetErrorCounter(void)
{
// TODO maybe fix this, but since this is test code, doesn't matter.
return 0;
return i2cErrorCount;
}
#endif

View file

@ -21,349 +21,425 @@
#include <platform.h>
#include "build_config.h"
#include "gpio.h"
#include "io.h"
#include "system.h"
#include "bus_i2c.h"
#include "nvic.h"
#include "io_impl.h"
#include "rcc.h"
#ifndef SOFT_I2C
// I2C2
// SCL PB10
// SDA PB11
// I2C1
// SCL PB6
// SDA PB7
#define CLOCKSPEED 800000 // i2c clockspeed 400kHz default (conform specs), 800kHz and 1200kHz (Betaflight default)
static void i2c_er_handler(void);
static void i2c_ev_handler(void);
static void i2cUnstick(void);
static void i2c_er_handler(I2CDevice device);
static void i2c_ev_handler(I2CDevice device);
static void i2cUnstick(IO_t scl, IO_t sda);
typedef struct i2cDevice_s {
I2C_TypeDef *dev;
GPIO_TypeDef *gpio;
uint16_t scl;
uint16_t sda;
uint8_t ev_irq;
uint8_t er_irq;
uint32_t peripheral;
} i2cDevice_t;
#define GPIO_AF_I2C GPIO_AF_I2C1
static const i2cDevice_t i2cHardwareMap[] = {
{ I2C1, GPIOB, Pin_6, Pin_7, I2C1_EV_IRQn, I2C1_ER_IRQn, RCC_APB1Periph_I2C1 },
{ I2C2, GPIOB, Pin_10, Pin_11, I2C2_EV_IRQn, I2C2_ER_IRQn, RCC_APB1Periph_I2C2 },
#ifdef STM32F4
#if defined(USE_I2C_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
#else
#define IOCFG_I2C IOCFG_AF_OD
#endif
#ifndef I2C1_SCL
#define I2C1_SCL PB8
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB9
#endif
#else
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
#ifdef STM32F4
#ifndef I2C3_SCL
#define I2C3_SCL PA8
#endif
#ifndef I2C3_SDA
#define I2C3_SDA PB4
#endif
#endif
static i2cDevice_t i2cHardwareMap[] = {
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn },
#ifdef STM32F4
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn }
#endif
};
// Copy of peripheral address for IRQ routines
static I2C_TypeDef *I2Cx = NULL;
// Copy of device index for reinit, etc purposes
static I2CDevice I2Cx_index;
static bool i2cOverClock;
void i2cSetOverclock(uint8_t OverClock) {
i2cOverClock = (OverClock) ? true : false;
}
void I2C1_ER_IRQHandler(void)
{
i2c_er_handler();
}
void I2C1_EV_IRQHandler(void)
{
i2c_ev_handler();
}
void I2C2_ER_IRQHandler(void)
{
i2c_er_handler();
}
void I2C2_EV_IRQHandler(void)
{
i2c_ev_handler();
}
#define I2C_DEFAULT_TIMEOUT 30000
static volatile uint16_t i2cErrorCount = 0;
static volatile bool error = false;
static volatile bool busy;
static i2cState_t i2cState[] = {
{ false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 }
};
static volatile uint8_t addr;
static volatile uint8_t reg;
static volatile uint8_t bytes;
static volatile uint8_t writing;
static volatile uint8_t reading;
static volatile uint8_t* write_p;
static volatile uint8_t* read_p;
static bool i2cOverClock;
static bool i2cHandleHardwareFailure(void)
void i2cSetOverclock(uint8_t overClock)
{
i2cOverClock = overClock ? true : false;
}
void I2C1_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_1);
}
void I2C1_EV_IRQHandler(void) {
i2c_ev_handler(I2CDEV_1);
}
void I2C2_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_2);
}
void I2C2_EV_IRQHandler(void) {
i2c_ev_handler(I2CDEV_2);
}
#ifdef STM32F4
void I2C3_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_3);
}
void I2C3_EV_IRQHandler(void) {
i2c_ev_handler(I2CDEV_3);
}
#endif
static bool i2cHandleHardwareFailure(I2CDevice device)
{
i2cErrorCount++;
// reinit peripheral + clock out garbage
i2cInit(I2Cx_index);
i2cInit(device);
return false;
}
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
addr = addr_ << 1;
reg = reg_;
writing = 1;
reading = 0;
write_p = data;
read_p = data;
bytes = len_;
busy = 1;
error = false;
if (!I2Cx)
if (device == I2CINVALID)
return false;
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
state->addr = addr_ << 1;
state->reg = reg_;
state->writing = 1;
state->reading = 0;
state->write_p = data;
state->read_p = data;
state->bytes = len_;
state->busy = 1;
state->error = false;
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
while (I2Cx->CR1 & 0x0200 && --timeout > 0) { ; } // wait for any stop to finish sending
if (timeout == 0) {
return i2cHandleHardwareFailure();
}
if (!(I2Cx->CR1 & I2C_CR1_START)) { // ensure sending a start
while (I2Cx->CR1 & I2C_CR1_STOP && --timeout > 0) {; } // wait for any stop to finish sending
if (timeout == 0)
return i2cHandleHardwareFailure(device);
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
}
timeout = I2C_DEFAULT_TIMEOUT;
while (busy && --timeout > 0) { ; }
if (timeout == 0) {
return i2cHandleHardwareFailure();
}
while (state->busy && --timeout > 0) {; }
if (timeout == 0)
return i2cHandleHardwareFailure(device);
return !error;
return !(state->error);
}
bool i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWriteBuffer(addr_, reg_, 1, &data);
return i2cWriteBuffer(device, addr_, reg_, 1, &data);
}
bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
addr = addr_ << 1;
reg = reg_;
writing = 0;
reading = 1;
read_p = buf;
write_p = buf;
bytes = len;
busy = 1;
error = false;
if (!I2Cx)
if (device == I2CINVALID)
return false;
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
state->addr = addr_ << 1;
state->reg = reg_;
state->writing = 0;
state->reading = 1;
state->read_p = buf;
state->write_p = buf;
state->bytes = len;
state->busy = 1;
state->error = false;
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
while (I2Cx->CR1 & 0x0200 && --timeout > 0) { ; } // wait for any stop to finish sending
if (!(I2Cx->CR1 & I2C_CR1_START)) { // ensure sending a start
while (I2Cx->CR1 & I2C_CR1_STOP && --timeout > 0) {; } // wait for any stop to finish sending
if (timeout == 0)
return i2cHandleHardwareFailure();
return i2cHandleHardwareFailure(device);
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
}
timeout = I2C_DEFAULT_TIMEOUT;
while (busy && --timeout > 0) { ; }
while (state->busy && --timeout > 0) {; }
if (timeout == 0)
return i2cHandleHardwareFailure();
return i2cHandleHardwareFailure(device);
return !error;
return !(state->error);
}
static void i2c_er_handler(void)
{
// Read the I2Cx status register
uint32_t SR1Register = I2Cx->SR1;
static void i2c_er_handler(I2CDevice device) {
if (SR1Register & 0x0F00) { // an error
error = true;
}
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
// Read the I2C1 status register
volatile uint32_t SR1Register = I2Cx->SR1;
if (SR1Register & 0x0F00) // an error
state->error = true;
// If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
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)
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop
if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
// TODO - busy waiting in highest priority IRQ. Maybe only set flag and handle it from main loop
while (I2Cx->CR1 & 0x0100) { ; } // wait for any start to finish sending
if (!(SR1Register & I2C_SR1_ARLO) && !(I2Cx->CR1 & I2C_CR1_STOP)) { // if we dont have an ARLO error, ensure sending of a stop
if (I2Cx->CR1 & I2C_CR1_START) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
while (I2Cx->CR1 & I2C_CR1_START) {; } // wait for any start to finish sending
I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
while (I2Cx->CR1 & 0x0200) { ; } // wait for stop to finish sending
i2cInit(I2Cx_index); // reset and configure the hardware
} else {
while (I2Cx->CR1 & I2C_CR1_STOP) {; } // wait for stop to finish sending
i2cInit(device); // reset and configure the hardware
}
else {
I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
}
}
}
I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
busy = 0;
state->busy = 0;
}
void i2c_ev_handler(void)
{
void i2c_ev_handler(I2CDevice device) {
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
static int8_t index; // index is signed -1 == send the subaddress
uint8_t SReg_1 = I2Cx->SR1; // read the status register here
if (SReg_1 & 0x0001) { // we just sent a start - EV5 in ref manual
I2Cx->CR1 &= ~0x0800; // reset the POS bit so ACK/NACK applied to the current byte
if (SReg_1 & I2C_SR1_SB) { // we just sent a start - EV5 in ref manual
I2Cx->CR1 &= ~I2C_CR1_POS; // reset the POS bit so ACK/NACK applied to the current byte
I2C_AcknowledgeConfig(I2Cx, ENABLE); // make sure ACK is on
index = 0; // reset the index
if (reading && (subaddress_sent || 0xFF == reg)) { // we have sent the subaddr
if (state->reading && (subaddress_sent || 0xFF == state->reg)) { // we have sent the subaddr
subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly
if (bytes == 2)
I2Cx->CR1 |= 0x0800; // set the POS bit so NACK applied to the final byte in the two byte read
I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Receiver); // send the address and set hardware mode
} else { // direction is Tx, or we havent sent the sub and rep start
I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Transmitter); // send the address and set hardware mode
if (reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
if (state->bytes == 2)
I2Cx->CR1 |= I2C_CR1_POS; // set the POS bit so NACK applied to the final byte in the two byte read
I2C_Send7bitAddress(I2Cx, state->addr, I2C_Direction_Receiver); // send the address and set hardware mode
}
else { // direction is Tx, or we havent sent the sub and rep start
I2C_Send7bitAddress(I2Cx, state->addr, I2C_Direction_Transmitter); // send the address and set hardware mode
if (state->reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
index = -1; // send a subaddress
}
} else if (SReg_1 & 0x0002) { // we just sent the address - EV6 in ref manual
}
else if (SReg_1 & I2C_SR1_ADDR) { // we just sent the address - EV6 in ref manual
// Read SR1,2 to clear ADDR
__DMB(); // memory fence to control hardware
if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
if (state->bytes == 1 && state->reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
__DMB();
(void)I2Cx->SR2; // clear ADDR after ACK is turned off
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
final_stop = 1;
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
} else { // EV6 and EV6_1
}
else { // EV6 and EV6_1
(void)I2Cx->SR2; // clear the ADDR here
__DMB();
if (bytes == 2 && reading && subaddress_sent) { // rx 2 bytes - EV6_1
if (state->bytes == 2 && state->reading && subaddress_sent) { // rx 2 bytes - EV6_1
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
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 (state->bytes == 3 && state->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
else // receiving greater than three bytes, sending subaddress, or transmitting
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 & I2C_SR1_BTF) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
final_stop = 1;
if (reading && subaddress_sent) { // EV7_2, EV7_3
if (bytes > 2) { // EV7_2
if (state->reading && subaddress_sent) { // EV7_2, EV7_3
if (state->bytes > 2) { // EV7_2
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
final_stop = 1; // required to fix hardware
read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7
} else { // EV7_3
}
else { // EV7_3
if (final_stop)
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
else
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
read_p[index++] = (uint8_t)I2Cx->DR; // read data N
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N
index++; // to show job completed
}
} else { // EV8_2, which may be due to a subaddress sent or a write completion
if (subaddress_sent || (writing)) {
}
else { // EV8_2, which may be due to a subaddress sent or a write completion
if (subaddress_sent || (state->writing)) {
if (final_stop)
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
else
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
index++; // to show that the job is complete
} else { // We need to send a subaddress
}
else { // We need to send a subaddress
I2C_GenerateSTART(I2Cx, ENABLE); // program the repeated Start
subaddress_sent = 1; // this is set back to zero upon completion of the current task
}
}
// TODO - busy waiting in ISR
// we must wait for the start to clear, otherwise we get constant BTF
while (I2Cx->CR1 & 0x0100) { ; }
} else if (SReg_1 & 0x0040) { // Byte received - EV7
read_p[index++] = (uint8_t)I2Cx->DR;
if (bytes == (index + 3))
while (I2Cx->CR1 & 0x0100) {; }
}
else if (SReg_1 & I2C_SR1_RXNE) { // Byte received - EV7
state->read_p[index++] = (uint8_t)I2Cx->DR;
if (state->bytes == (index + 3))
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2
if (bytes == index) // We have completed a final EV7
if (state->bytes == index) // We have completed a final EV7
index++; // to show job is complete
} else if (SReg_1 & 0x0080) { // Byte transmitted EV8 / EV8_1
}
else if (SReg_1 & I2C_SR1_TXE) { // Byte transmitted EV8 / EV8_1
if (index != -1) { // we dont have a subaddress to send
I2Cx->DR = write_p[index++];
if (bytes == index) // we have sent all the data
I2Cx->DR = state->write_p[index++];
if (state->bytes == index) // we have sent all the data
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
} else {
}
else {
index++;
I2Cx->DR = reg; // send the subaddress
if (reading || !bytes) // if receiving or sending 0 bytes, flush now
I2Cx->DR = state->reg; // send the subaddress
if (state->reading || !(state->bytes)) // if receiving or sending 0 bytes, flush now
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
}
}
if (index == bytes + 1) { // we have completed the current job
if (index == state->bytes + 1) { // we have completed the current job
subaddress_sent = 0; // reset this here
if (final_stop) // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
busy = 0;
state->busy = 0;
}
}
void i2cInit(I2CDevice index)
void i2cInit(I2CDevice device)
{
if (device == I2CINVALID)
return;
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
NVIC_InitTypeDef nvic;
I2C_InitTypeDef i2c;
I2C_InitTypeDef i2cInit;
if (index > I2CDEV_MAX)
index = I2CDEV_MAX;
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
// Turn on peripheral clock, save device and index
I2Cx = i2cHardwareMap[index].dev;
I2Cx_index = index;
RCC_APB1PeriphClockCmd(i2cHardwareMap[index].peripheral, ENABLE);
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
// diable I2C interrrupts first to avoid ER handler triggering
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
// Enable RCC
RCC_ClockCmd(i2c->rcc, ENABLE);
// clock out stuff to make sure slaves arent stuck
// This will also configure GPIO as AF_OD at the end
i2cUnstick();
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
// Init I2C peripheral
I2C_DeInit(I2Cx);
I2C_StructInit(&i2c);
i2cUnstick(scl, sda);
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request
i2c.I2C_Mode = I2C_Mode_I2C;
i2c.I2C_DutyCycle = I2C_DutyCycle_2;
i2c.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
// Init pins
#ifdef STM32F4
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
#else
IOConfigGPIO(scl, IOCFG_AF_OD);
IOConfigGPIO(sda, IOCFG_AF_OD);
#endif
if (i2cOverClock) {
i2c.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
I2C_DeInit(i2c->dev);
I2C_StructInit(&i2cInit);
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request
i2cInit.I2C_Mode = I2C_Mode_I2C;
i2cInit.I2C_DutyCycle = I2C_DutyCycle_2;
i2cInit.I2C_OwnAddress1 = 0;
i2cInit.I2C_Ack = I2C_Ack_Enable;
i2cInit.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
if (i2c->overClock) {
i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
} else {
i2c.I2C_ClockSpeed = 400000; // 400khz Operation according specs
i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs
}
I2C_Cmd(I2Cx, ENABLE);
I2C_Init(I2Cx, &i2c);
I2C_Cmd(i2c->dev, ENABLE);
I2C_Init(i2c->dev, &i2cInit);
I2C_StretchClockCmd(i2c->dev, ENABLE);
// I2C ER Interrupt
nvic.NVIC_IRQChannel = i2cHardwareMap[index].er_irq;
nvic.NVIC_IRQChannel = i2c->er_irq;
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER);
nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER);
nvic.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic);
// I2C EV Interrupt
nvic.NVIC_IRQChannel = i2cHardwareMap[index].ev_irq;
nvic.NVIC_IRQChannel = i2c->ev_irq;
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV);
nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV);
NVIC_Init(&nvic);
@ -374,54 +450,39 @@ uint16_t i2cGetErrorCounter(void)
return i2cErrorCount;
}
static void i2cUnstick(void)
static void i2cUnstick(IO_t scl, IO_t sda)
{
GPIO_TypeDef *gpio;
gpio_config_t cfg;
uint16_t scl, sda;
int i;
int timeout = 100;
// prepare pins
gpio = i2cHardwareMap[I2Cx_index].gpio;
scl = i2cHardwareMap[I2Cx_index].scl;
sda = i2cHardwareMap[I2Cx_index].sda;
IOHi(scl);
IOHi(sda);
digitalHi(gpio, scl | sda);
cfg.pin = scl | sda;
cfg.speed = Speed_2MHz;
cfg.mode = Mode_Out_OD;
gpioInit(gpio, &cfg);
IOConfigGPIO(scl, IOCFG_OUT_OD);
IOConfigGPIO(sda, IOCFG_OUT_OD);
for (i = 0; i < 8; i++) {
// Wait for any clock stretching to finish
while (!digitalIn(gpio, scl))
while (!IORead(scl) && timeout) {
delayMicroseconds(10);
timeout--;
}
// Pull low
digitalLo(gpio, scl); // Set bus low
IOLo(scl); // Set bus low
delayMicroseconds(10);
// Release high again
digitalHi(gpio, scl); // Set bus high
IOHi(scl); // Set bus high
delayMicroseconds(10);
}
// Generate a start then stop condition
// SCL PB10
// SDA PB11
digitalLo(gpio, sda); // Set bus data low
IOLo(sda); // Set bus data low
delayMicroseconds(10);
digitalLo(gpio, scl); // Set bus scl low
IOLo(scl); // Set bus scl low
delayMicroseconds(10);
digitalHi(gpio, scl); // Set bus scl high
IOHi(scl); // Set bus scl high
delayMicroseconds(10);
digitalHi(gpio, sda); // Set bus sda high
// Init pins
cfg.pin = scl | sda;
cfg.speed = Speed_2MHz;
cfg.mode = Mode_AF_OD;
gpioInit(gpio, &cfg);
IOHi(sda); // Set bus sda high
}
#endif

View file

@ -17,208 +17,125 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <platform.h>
#include "build_config.h"
#include "gpio.h"
#include "system.h"
#include "drivers/io_impl.h"
#include "bus_i2c.h"
#ifndef SOFT_I2C
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#if !defined(I2C1_SCL_GPIO)
#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(USE_I2C_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
#else
#define IOCFG_I2C IOCFG_AF_OD
#endif
#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_HIGHSPEED_TIMING 0x00500E30 // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
#define I2C_STANDARD_TIMING 0x00E0257A // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
#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 = I2C1_OVERCLOCK },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK }
};
static bool i2cOverClock;
void i2cSetOverclock(uint8_t overClock)
{
i2cOverClock = overClock ? true : false;
}
///////////////////////////////////////////////////////////////////////////////
// I2C TimeoutUserCallback
///////////////////////////////////////////////////////////////////////////////
static bool i2cOverClock;
void i2cSetOverclock(uint8_t OverClock) {
i2cOverClock = (OverClock) ? true : false;
}
uint32_t i2cTimeoutUserCallback(I2C_TypeDef *I2Cx)
uint32_t i2cTimeoutUserCallback(void)
{
if (I2Cx == I2C1) {
i2c1ErrorCount++;
} else {
i2c2ErrorCount++;
}
i2cErrorCount++;
return false;
}
void i2cInitPort(I2C_TypeDef *I2Cx)
void i2cInit(I2CDevice device)
{
GPIO_InitTypeDef GPIO_InitStructure;
I2C_InitTypeDef I2C_InitStructure;
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);
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
I2C_TypeDef *I2Cx;
I2Cx = i2c->dev;
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);
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
GPIO_StructInit(&GPIO_InitStructure);
I2C_StructInit(&I2C_InitStructure);
RCC_ClockCmd(i2c->rcc, ENABLE);
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
// Init pins
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
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;
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
GPIO_InitStructure.GPIO_Pin = I2C1_SCL_PIN;
GPIO_Init(I2C1_SCL_GPIO, &GPIO_InitStructure);
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 = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
};
GPIO_InitStructure.GPIO_Pin = I2C1_SDA_PIN;
GPIO_Init(I2C1_SDA_GPIO, &GPIO_InitStructure);
I2C_Init(I2Cx, &i2cInit);
I2C_StructInit(&I2C_InitStructure);
I2C_StretchClockCmd(I2Cx, ENABLE);
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;
if (i2cOverClock) {
I2C_InitStructure.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
} else {
I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10
}
//I2C_InitStructure.I2C_Timing = 0x8000050B;
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;
// FIXME timing is board specific
//I2C_InitStructure.I2C_Timing = 0x00310309; // //400kHz I2C @ 8MHz input -> PRESC=0x0, SCLDEL=0x3, SDADEL=0x1, SCLH=0x03, SCLL=0x09 - value from TauLabs/Sparky
// ^ when using this setting and after a few seconds of a scope probe being attached to the I2C bus it was observed that the bus enters
// a busy state and does not recover.
if (i2cOverClock) {
I2C_InitStructure.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
} else {
I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10
}
//I2C_InitStructure.I2C_Timing = 0x8000050B;
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 i2c2ErrorCount;
return i2cErrorCount;
}
bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
bool i2cWrite(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(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -229,7 +146,7 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -241,7 +158,7 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
{
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -252,7 +169,7 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -263,7 +180,7 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -273,15 +190,18 @@ bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
return true;
}
bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
bool i2cRead(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(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -292,7 +212,7 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -303,7 +223,7 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -316,7 +236,7 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -333,7 +253,7 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
return i2cTimeoutUserCallback();
}
}
@ -345,3 +265,4 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
}
#endif

View file

@ -21,3 +21,7 @@ typedef struct mag_s {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
} mag_t;
#ifndef MAG_I2C_INSTANCE
#define MAG_I2C_INSTANCE I2C_DEVICE
#endif

View file

@ -20,10 +20,12 @@
#include <math.h>
#include "build_config.h"
#include <platform.h>
#ifdef USE_MAG_AK8975
#include "build_config.h"
#include "common/axis.h"
#include "common/maths.h"
@ -63,7 +65,7 @@ bool ak8975Detect(mag_t *mag)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
if (!ack || sig != 'H') // 0x48 / 01001000 / 'H'
return false;
@ -85,24 +87,24 @@ void ak8975Init()
UNUSED(ack);
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
delay(20);
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
delay(10);
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
delay(10);
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
delay(10);
// Clear status registers
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
// Trigger first measurement
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
}
#define BIT_STATUS1_REG_DATA_READY (1 << 0)
@ -117,13 +119,13 @@ bool ak8975Read(int16_t *magData)
uint8_t status;
uint8_t buf[6];
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
if (!ack || (status & BIT_STATUS1_REG_DATA_READY) == 0) {
return false;
}
#if 1 // USE_I2C_SINGLE_BYTE_READS
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
#else
for (uint8_t i = 0; i < 6; i++) {
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL + i, 1, &buf[i]); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
@ -133,7 +135,7 @@ bool ak8975Read(int16_t *magData)
}
#endif
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
if (!ack) {
return false;
}
@ -151,6 +153,8 @@ bool ak8975Read(int16_t *magData)
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * 4;
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
return true;
}
#endif

View file

@ -17,11 +17,13 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <math.h>
#include "platform.h"
#ifdef USE_MAG_HMC5883
#include "debug.h"
#include "common/axis.h"
@ -29,7 +31,8 @@
#include "system.h"
#include "nvic.h"
#include "gpio.h"
#include "io.h"
#include "exti.h"
#include "bus_i2c.h"
#include "light_led.h"
@ -120,14 +123,14 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f };
static const hmc5883Config_t *hmc5883Config = NULL;
void MAG_DATA_READY_EXTI_Handler(void)
#ifdef USE_MAG_DATA_READY_SIGNAL
static IO_t intIO;
static extiCallbackRec_t hmc5883_extiCallbackRec;
void hmc5883_extiHandler(extiCallbackRec_t* cb)
{
if (EXTI_GetITStatus(hmc5883Config->exti_line) == RESET) {
return;
}
EXTI_ClearITPendingBit(hmc5883Config->exti_line);
UNUSED(cb);
#ifdef DEBUG_MAG_DATA_READY_INTERRUPT
// Measure the delta between calls to the interrupt handler
// currently should be around 65/66 milli seconds / 15hz output rate
@ -143,57 +146,26 @@ void MAG_DATA_READY_EXTI_Handler(void)
lastCalledAt = now;
#endif
}
#endif
static void hmc5883lConfigureDataReadyInterruptHandling(void)
{
#ifdef USE_MAG_DATA_READY_SIGNAL
if (!(hmc5883Config->exti_port_source && hmc5883Config->exti_pin_source)) {
if (!(hmc5883Config->intTag)) {
return;
}
#ifdef STM32F10X
// enable AFIO for EXTI support
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
#ifdef STM32F303xC
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
#ifdef STM32F10X
gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source);
#endif
#ifdef STM32F303xC
gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source);
#endif
intIO = IOGetByTag(hmc5883Config->intTag);
#ifdef ENSURE_MAG_DATA_READY_IS_HIGH
uint8_t status = GPIO_ReadInputDataBit(hmc5883Config->gpioPort, hmc5883Config->gpioPin);
uint8_t status = IORead(intIO);
if (!status) {
return;
}
#endif
registerExtiCallbackHandler(hmc5883Config->exti_irqn, MAG_DATA_READY_EXTI_Handler);
EXTI_ClearITPendingBit(hmc5883Config->exti_line);
EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = hmc5883Config->exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Falling;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = hmc5883Config->exti_irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MAG_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MAG_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler);
EXTIConfig(intIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(intIO, true);
#endif
}
@ -204,7 +176,7 @@ bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
hmc5883Config = hmc5883ConfigToUse;
ack = i2cRead(MAG_ADDRESS, 0x0A, 1, &sig);
ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
if (!ack || sig != 'H')
return false;
@ -221,35 +193,16 @@ void hmc5883lInit(void)
int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow.
bool bret = true; // Error indicator
gpio_config_t gpio;
if (hmc5883Config) {
#ifdef STM32F303
if (hmc5883Config->gpioAHBPeripherals) {
RCC_AHBPeriphClockCmd(hmc5883Config->gpioAHBPeripherals, ENABLE);
}
#endif
#ifdef STM32F10X
if (hmc5883Config->gpioAPB2Peripherals) {
RCC_APB2PeriphClockCmd(hmc5883Config->gpioAPB2Peripherals, ENABLE);
}
#endif
gpio.pin = hmc5883Config->gpioPin;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(hmc5883Config->gpioPort, &gpio);
}
delay(50);
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
// The new gain setting is effective from the second measurement and on.
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
delay(100);
hmc5883lRead(magADC);
for (i = 0; i < 10; i++) { // Collect 10 samples
i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 1);
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
delay(50);
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
@ -267,9 +220,9 @@ void hmc5883lInit(void)
}
// Apply the negative bias. (Same gain)
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
for (i = 0; i < 10; i++) {
i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 1);
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
delay(50);
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
@ -291,9 +244,9 @@ void hmc5883lInit(void)
magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]);
// leave test mode
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
delay(100);
if (!bret) { // Something went wrong so get a best guess
@ -309,7 +262,7 @@ bool hmc5883lRead(int16_t *magData)
{
uint8_t buf[6];
bool ack = i2cRead(MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
if (!ack) {
return false;
}
@ -321,3 +274,5 @@ bool hmc5883lRead(int16_t *magData)
return true;
}
#endif

View file

@ -17,20 +17,10 @@
#pragma once
typedef struct hmc5883Config_s {
#ifdef STM32F303
uint32_t gpioAHBPeripherals;
#endif
#ifdef STM32F10X
uint32_t gpioAPB2Peripherals;
#endif
uint16_t gpioPin;
GPIO_TypeDef *gpioPort;
#include "io.h"
uint8_t exti_port_source;
uint32_t exti_line;
uint8_t exti_pin_source;
IRQn_Type exti_irqn;
typedef struct hmc5883Config_s {
ioTag_t intTag;
} hmc5883Config_t;
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);

View file

@ -20,10 +20,12 @@
#include <math.h>
#include "build_config.h"
#include "platform.h"
#ifdef USE_MAG_MAG3110
#include "build_config.h"
#include "common/axis.h"
#include "common/maths.h"
@ -39,7 +41,6 @@
#include "compass_mag3110.h"
#ifdef USE_MAG_MAG3110
#define MAG3110_MAG_I2C_ADDRESS 0x0E
@ -62,7 +63,7 @@ bool mag3110detect(mag_t *mag)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_WHO_AM_I, 1, &sig);
ack = i2cRead(MAG_I2C_INSTANCE, MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_WHO_AM_I, 1, &sig);
if (!ack || sig != 0xC4)
return false;
@ -77,10 +78,10 @@ void mag3110Init()
bool ack;
UNUSED(ack);
ack = i2cWrite(MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_CTRL_REG1, 0x01); // active mode 80 Hz ODR with OSR = 1
ack = i2cWrite(MAG_I2C_INSTANCE, MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_CTRL_REG1, 0x01); // active mode 80 Hz ODR with OSR = 1
delay(20);
ack = i2cWrite(MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_CTRL_REG2, 0xA0); // AUTO_MRST_EN + RAW
ack = i2cWrite(MAG_I2C_INSTANCE, MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_CTRL_REG2, 0xA0); // AUTO_MRST_EN + RAW
delay(10);
}
@ -93,12 +94,12 @@ bool mag3110Read(int16_t *magData)
uint8_t status;
uint8_t buf[6];
ack = i2cRead(MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_STATUS, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_STATUS, 1, &status);
if (!ack || (status & BIT_STATUS_REG_DATA_READY) == 0) {
return false;
}
ack = i2cRead(MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_HXL, 6, buf);
ack = i2cRead(MAG_I2C_INSTANCE, MAG3110_MAG_I2C_ADDRESS, MAG3110_MAG_REG_HXL, 6, buf);
magData[X] = (int16_t)(buf[0] << 8 | buf[1]);
magData[Y] = (int16_t)(buf[2] << 8 | buf[3]);

View file

@ -17,7 +17,6 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
@ -26,6 +25,10 @@
#include "display_ug2864hsweg01.h"
#ifndef OLED_I2C_INSTANCE
#define OLED_I2C_INSTANCE I2CDEV_1
#endif
#define INVERSE_CHAR_FORMAT 0x7f // 0b01111111
#define NORMAL_CHAR_FORMAT 0x00 // 0b00000000
@ -172,12 +175,12 @@ static const uint8_t multiWiiFont[][5] = { // Refer to "Times New Roman" Font Da
static bool i2c_OLED_send_cmd(uint8_t command)
{
return i2cWrite(OLED_address, 0x80, command);
return i2cWrite(OLED_I2C_INSTANCE, OLED_address, 0x80, command);
}
bool i2c_OLED_send_byte(uint8_t val)
{
return i2cWrite(OLED_address, 0x40, val);
return i2cWrite(OLED_I2C_INSTANCE, OLED_address, 0x40, val);
}
void i2c_OLED_clear_display(void)

183
src/main/drivers/exti.c Normal file
View file

@ -0,0 +1,183 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#include "nvic.h"
#include "io_impl.h"
#include "exti.h"
#ifdef USE_EXTI
typedef struct {
extiCallbackRec_t* handler;
} extiChannelRec_t;
extiChannelRec_t extiChannelRecs[16];
// IRQ gouping, same on 103 and 303
#define EXTI_IRQ_GROUPS 7
// 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
static const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 };
static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS];
#if defined(STM32F1) || defined(STM32F4)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn,
EXTI1_IRQn,
EXTI2_IRQn,
EXTI3_IRQn,
EXTI4_IRQn,
EXTI9_5_IRQn,
EXTI15_10_IRQn
};
#elif defined(STM32F3)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
EXTI0_IRQn,
EXTI1_IRQn,
EXTI2_TS_IRQn,
EXTI3_IRQn,
EXTI4_IRQn,
EXTI9_5_IRQn,
EXTI15_10_IRQn
};
#else
# warning "Unknown CPU"
#endif
void EXTIInit(void)
{
#if defined(STM32F1)
// enable AFIO for EXTI support
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
#if defined(STM32F3) || defined(STM32F4)
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
memset(extiChannelRecs, 0, sizeof(extiChannelRecs));
memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority));
}
void EXTIHandlerInit(extiCallbackRec_t *self, extiHandlerCallback *fn)
{
self->fn = fn;
}
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger)
{
int chIdx;
chIdx = IO_GPIOPinIdx(io);
if(chIdx < 0)
return;
extiChannelRec_t *rec = &extiChannelRecs[chIdx];
int group = extiGroups[chIdx];
rec->handler = cb;
#if defined(STM32F10X)
GPIO_EXTILineConfig(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io));
#elif defined(STM32F303xC)
SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io));
#elif defined(STM32F4)
SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io));
#else
# warning "Unknown CPU"
#endif
uint32_t extiLine = IO_EXTI_Line(io);
EXTI_ClearITPendingBit(extiLine);
EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = extiLine;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = trigger;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
if(extiGroupPriority[group] > irqPriority) {
extiGroupPriority[group] = irqPriority;
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = extiGroupIRQn[group];
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
}
void EXTIRelease(IO_t io)
{
// don't forget to match cleanup with config
EXTIEnable(io, false);
int chIdx;
chIdx = IO_GPIOPinIdx(io);
if(chIdx < 0)
return;
extiChannelRec_t *rec = &extiChannelRecs[chIdx];
rec->handler = NULL;
}
void EXTIEnable(IO_t io, bool enable)
{
#if defined(STM32F1) || defined(STM32F4)
uint32_t extiLine = IO_EXTI_Line(io);
if(!extiLine)
return;
if(enable)
EXTI->IMR |= extiLine;
else
EXTI->IMR &= ~extiLine;
#elif defined(STM32F303xC)
int extiLine = IO_EXTI_Line(io);
if(extiLine < 0)
return;
// assume extiLine < 32 (valid for all EXTI pins)
if(enable)
EXTI->IMR |= 1 << extiLine;
else
EXTI->IMR &= ~(1 << extiLine);
#else
# error "Unsupported target"
#endif
}
void EXTI_IRQHandler(void)
{
uint32_t exti_active = EXTI->IMR & EXTI->PR;
while(exti_active) {
unsigned idx = 31 - __builtin_clz(exti_active);
uint32_t mask = 1 << idx;
extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler);
EXTI->PR = mask; // clear pending mask (by writing 1)
exti_active &= ~mask;
}
}
#define _EXTI_IRQ_HANDLER(name) \
void name(void) { \
EXTI_IRQHandler(); \
} \
struct dummy \
/**/
_EXTI_IRQ_HANDLER(EXTI0_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI1_IRQHandler);
#if defined(STM32F1)
_EXTI_IRQ_HANDLER(EXTI2_IRQHandler);
#elif defined(STM32F3) || defined(STM32F4)
_EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler);
#else
# warning "Unknown CPU"
#endif
_EXTI_IRQ_HANDLER(EXTI3_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI4_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler);
#endif

View file

@ -18,18 +18,23 @@
#pragma once
typedef struct extiConfig_s {
#ifdef STM32F303
uint32_t gpioAHBPeripherals;
#endif
#ifdef STM32F10X
uint32_t gpioAPB2Peripherals;
#endif
uint16_t gpioPin;
GPIO_TypeDef *gpioPort;
#include "drivers/io.h"
uint8_t exti_port_source;
uint32_t exti_line;
uint8_t exti_pin_source;
IRQn_Type exti_irqn;
// old EXTI interface, to be replaced
typedef struct extiConfig_s {
ioTag_t tag;
} extiConfig_t;
typedef struct extiCallbackRec_s extiCallbackRec_t;
typedef void extiHandlerCallback(extiCallbackRec_t *self);
struct extiCallbackRec_s {
extiHandlerCallback *fn;
};
void EXTIInit(void);
void EXTIHandlerInit(extiCallbackRec_t *cb, extiHandlerCallback *fn);
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger);
void EXTIRelease(IO_t io);
void EXTIEnable(IO_t io, bool enable);

View file

@ -112,6 +112,7 @@ static inline void digitalToggle(GPIO_TypeDef *p, uint16_t i) { p->ODR ^= i; }
static inline uint16_t digitalIn(GPIO_TypeDef *p, uint16_t i) { return p->IDR & i; }
#endif
void gpioInit(GPIO_TypeDef *gpio, const gpio_config_t *config);
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config);
void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc);
void gpioPinRemapConfig(uint32_t remap, bool enable);

View file

@ -22,7 +22,7 @@
#include "gpio.h"
void gpioInit(GPIO_TypeDef *gpio, const gpio_config_t *config)
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
{
uint32_t pinpos;
for (pinpos = 0; pinpos < 16; pinpos++) {

View file

@ -20,8 +20,6 @@
#include "platform.h"
#include "build_config.h"
#include "gpio.h"
#define MODE_OFFSET 0
@ -36,7 +34,7 @@
//#define GPIO_Speed_2MHz GPIO_Speed_Level_2 Medium Speed:2MHz
//#define GPIO_Speed_50MHz GPIO_Speed_Level_3 High Speed:50MHz
void gpioInit(GPIO_TypeDef *gpio, const gpio_config_t *config)
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
{
GPIO_InitTypeDef GPIO_InitStructure;

View file

@ -28,6 +28,10 @@
#include "system.h"
#include "bus_i2c.h"
#ifndef GPS_I2C_INSTANCE
#define GPS_I2C_INSTANCE I2CDEV_1
#endif
#define I2C_GPS_ADDRESS 0x20 //7 bits
#define I2C_GPS_STATUS_00 00 //(Read only)
@ -47,7 +51,7 @@ bool i2cnavGPSModuleDetect(void)
bool ack;
uint8_t i2cGpsStatus;
ack = i2cRead(I2C_GPS_ADDRESS, I2C_GPS_STATUS_00, 1, &i2cGpsStatus); /* status register */
ack = i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_STATUS_00, 1, &i2cGpsStatus); /* status register */
if (ack)
return true;
@ -57,14 +61,12 @@ bool i2cnavGPSModuleDetect(void)
void i2cnavGPSModuleRead(gpsDataI2CNAV_t * gpsMsg)
{
bool ack;
uint8_t i2cGpsStatus;
gpsMsg->flags.newData = 0;
gpsMsg->flags.fix3D = 0;
gpsMsg->flags.gpsOk = 0;
ack = i2cRead(I2C_GPS_ADDRESS, I2C_GPS_STATUS_00, 1, &i2cGpsStatus); /* status register */
uint8_t i2cGpsStatus;
bool ack = i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_STATUS_00, 1, &i2cGpsStatus); /* status register */
if (!ack)
return;
@ -76,11 +78,11 @@ void i2cnavGPSModuleRead(gpsDataI2CNAV_t * gpsMsg)
gpsMsg->flags.fix3D = 1;
if (i2cGpsStatus & I2C_GPS_STATUS_NEW_DATA) {
i2cRead(I2C_GPS_ADDRESS, I2C_GPS_LOCATION, 4, (uint8_t*)&gpsMsg->latitude);
i2cRead(I2C_GPS_ADDRESS, I2C_GPS_LOCATION + 4, 4, (uint8_t*)&gpsMsg->longitude);
i2cRead(I2C_GPS_ADDRESS, I2C_GPS_GROUND_SPEED, 2, (uint8_t*)&gpsMsg->speed);
i2cRead(I2C_GPS_ADDRESS, I2C_GPS_GROUND_COURSE, 2, (uint8_t*)&gpsMsg->ground_course);
i2cRead(I2C_GPS_ADDRESS, I2C_GPS_ALTITUDE, 2, (uint8_t*)&gpsMsg->altitude);
i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_LOCATION, 4, (uint8_t*)&gpsMsg->latitude);
i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_LOCATION + 4, 4, (uint8_t*)&gpsMsg->longitude);
i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_GROUND_SPEED, 2, (uint8_t*)&gpsMsg->speed);
i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_GROUND_COURSE, 2, (uint8_t*)&gpsMsg->ground_course);
i2cRead(GPS_I2C_INSTANCE, I2C_GPS_ADDRESS, I2C_GPS_ALTITUDE, 2, (uint8_t*)&gpsMsg->altitude);
gpsMsg->hdop = 0;

View file

@ -38,10 +38,7 @@ static uint8_t mpuDividerDrops;
bool getMpuDataStatus(gyro_t *gyro)
{
bool mpuDataStatus;
gyro->intStatus(&mpuDataStatus);
return mpuDataStatus;
return gyro->intStatus();
}
bool gyroSyncCheckUpdate(void)

View file

@ -6,7 +6,11 @@
// can't use 0
#define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1)
#define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_BARO_EXT NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_BARO_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_SONAR_EXTI NVIC_BUILD_PRIORITY(2, 0) // maybe increate slightly
#define NVIC_PRIO_TRANSPONDER_DMA NVIC_BUILD_PRIORITY(3, 0)
#define NVIC_PRIO_MPU_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1)
@ -17,6 +21,15 @@
#define NVIC_PRIO_SERIALUART3_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART3_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART3 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART4_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART4_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART4 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART5_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART5_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART5 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART6_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART6_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART6 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_I2C_ER NVIC_BUILD_PRIORITY(0, 0)
#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0)
#define NVIC_PRIO_USB NVIC_BUILD_PRIORITY(2, 0)
@ -25,6 +38,7 @@
#define NVIC_PRIO_MPU_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAX7456_DMA NVIC_BUILD_PRIORITY(3, 0)
// utility macros to join/split priority
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4)&0xf0)

View file

@ -175,12 +175,11 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
#endif
#ifdef SONAR
if (init->sonarGPIOConfig && IO_GPIOBYTAG(timerHardwarePtr->tag) == init->sonarGPIOConfig->gpio &&
if (init->useSonar &&
(
IO_PINBYTAG(timerHardwarePtr->tag) == init->sonarGPIOConfig->triggerPin ||
IO_PINBYTAG(timerHardwarePtr->tag) == init->sonarGPIOConfig->echoPin
)
) {
timerHardwarePtr->tag == init->sonarIOConfig.triggerTag ||
timerHardwarePtr->tag == init->sonarIOConfig.echoTag
)) {
continue;
}
#endif

View file

@ -48,11 +48,10 @@
#define PWM_BRUSHED_TIMER_MHZ 8
typedef struct sonarGPIOConfig_s {
GPIO_TypeDef *gpio;
uint16_t triggerPin;
uint16_t echoPin;
} sonarGPIOConfig_t;
typedef struct sonarIOConfig_s {
ioTag_t triggerTag;
ioTag_t echoTag;
} sonarIOConfig_t;
typedef struct drv_pwm_config_s {
bool useParallelPWM;
@ -83,7 +82,7 @@ typedef struct drv_pwm_config_s {
uint16_t motorPwmRate;
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
// some higher value (used by 3d mode), or 0, for brushed pwm drivers.
sonarGPIOConfig_t *sonarGPIOConfig;
sonarIOConfig_t sonarIOConfig;
} drv_pwm_config_t;

View file

@ -20,7 +20,6 @@
#include <platform.h>
#ifndef SKIP_RX_PWM_PPM
#include "build_config.h"

View file

@ -22,4 +22,4 @@ typedef void (*sensorInitFuncPtr)(void); // sensor init proto
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
typedef void (*sensorAccInitFuncPtr)(struct acc_s *acc); // sensor init prototype
typedef void (*sensorGyroInitFuncPtr)(uint8_t lpf); // gyro sensor init prototype
typedef void (*sensorInterruptFuncPtr)(bool *data); // sensor read and align prototype
typedef bool (*sensorInterruptFuncPtr)(void); // sensor Interrupt Data Ready

View file

@ -19,13 +19,16 @@
#include <stdint.h>
#include <platform.h>
#include "build_config.h"
#if defined(SONAR)
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/nvic.h"
#include "build_config.h"
#include "system.h"
#include "exti.h"
#include "io.h"
#include "gpio.h"
#include "nvic.h"
#include "drivers/rangefinder.h"
#include "drivers/sonar_hcsr04.h"
@ -47,12 +50,20 @@
STATIC_UNIT_TESTED volatile int32_t hcsr04SonarPulseTravelTime = 0;
sonarHcsr04Hardware_t sonarHcsr04Hardware;
#ifdef USE_EXTI
static extiCallbackRec_t hcsr04_extiCallbackRec;
#endif
static IO_t echoIO;
static IO_t triggerIO;
#if !defined(UNIT_TEST)
static void ECHO_EXTI_IRQHandler(void)
void hcsr04_extiHandler(extiCallbackRec_t* cb)
{
static uint32_t timing_start;
UNUSED(cb);
if (digitalIn(sonarHcsr04Hardware.echo_gpio, sonarHcsr04Hardware.echo_pin) != 0) {
if (IORead(echoIO) != 0) {
timing_start = micros();
} else {
const uint32_t timing_stop = micros();
@ -60,23 +71,6 @@ static void ECHO_EXTI_IRQHandler(void)
hcsr04SonarPulseTravelTime = timing_stop - timing_start;
}
}
EXTI_ClearITPendingBit(sonarHcsr04Hardware.exti_line);
}
void EXTI0_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void EXTI1_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void EXTI9_5_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
#endif
@ -96,42 +90,23 @@ void hcsr04_set_sonar_hardware(void)
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
gpio_config_t gpio;
// trigger pin
gpio.pin = sonarHcsr04Hardware.trigger_pin;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpioInit(sonarHcsr04Hardware.trigger_gpio, &gpio);
triggerIO = IOGetByTag(sonarHcsr04Hardware.triggerTag);
IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0);
IOConfigGPIO(triggerIO, IOCFG_OUT_PP);
// echo pin
gpio.pin = sonarHcsr04Hardware.echo_pin;
gpio.mode = Mode_IN_FLOATING;
gpioInit(sonarHcsr04Hardware.echo_gpio, &gpio);
echoIO = IOGetByTag(sonarHcsr04Hardware.echoTag);
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0);
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
#ifdef STM32F10X
// setup external interrupt on echo pin
gpioExtiLineConfig(GPIO_PortSourceGPIOB, sonarHcsr04Hardware.exti_pin_source);
#ifdef USE_EXTI
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
EXTIEnable(echoIO, true);
#endif
#ifdef STM32F303xC
gpioExtiLineConfig(EXTI_PortSourceGPIOB, sonarHcsr04Hardware.exti_pin_source);
#endif
EXTI_ClearITPendingBit(sonarHcsr04Hardware.exti_line);
EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = sonarHcsr04Hardware.exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = sonarHcsr04Hardware.exti_irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SONAR_ECHO);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SONAR_ECHO);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif
#endif // UNIT_TEST
}
void hcsr04_init(rangefinder_t *rangefinder)
@ -156,10 +131,10 @@ void hcsr04_start_reading(void)
const uint32_t timeNowMs = millis();
if (timeNowMs > timeOfLastMeasurementMs + HCSR04_MinimumFiringIntervalMs) {
timeOfLastMeasurementMs = timeNowMs;
digitalHi(sonarHcsr04Hardware.trigger_gpio, sonarHcsr04Hardware.trigger_pin);
IOHi(triggerIO);
// The width of trigger signal must be greater than 10us, according to device spec
delayMicroseconds(11);
digitalLo(sonarHcsr04Hardware.trigger_gpio, sonarHcsr04Hardware.trigger_pin);
IOLo(triggerIO);
}
#endif
}

View file

@ -18,13 +18,8 @@
#pragma once
typedef struct sonarHcsr04Hardware_s {
uint16_t trigger_pin;
GPIO_TypeDef* trigger_gpio;
uint16_t echo_pin;
GPIO_TypeDef* echo_gpio;
uint32_t exti_line;
uint8_t exti_pin_source;
IRQn_Type exti_irqn;
ioTag_t triggerTag;
ioTag_t echoTag;
} sonarHcsr04Hardware_t;
struct rangefinder_s;

View file

@ -19,16 +19,20 @@
#include <stdint.h>
#include "platform.h"
#include "build_config.h"
#if defined(SONAR) && defined(USE_SONAR_SRF10)
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/bus_i2c.h"
#include "drivers/rangefinder.h"
#include "drivers/sonar_srf10.h"
#ifndef SRF10_I2C_INSTANCE
#define SRF10_I2C_INSTANCE I2CDEV_1
#endif
// Technical specification is at: http://robot-electronics.co.uk/htm/srf10tech.htm
#define SRF10_MAX_RANGE_CM 600 // 6m, from SFR10 spec sheet
@ -94,18 +98,18 @@ bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf) {UNUSED(addr
static bool i2c_srf10_send_command(uint8_t command)
{
return i2cWrite(SRF10_AddressI2C, SRF10_WRITE_CommandRegister, command);
return i2cWrite(SRF10_I2C_INSTANCE, SRF10_AddressI2C, SRF10_WRITE_CommandRegister, command);
}
static bool i2c_srf10_send_byte(uint8_t i2cRegister, uint8_t val)
{
return i2cWrite(SRF10_AddressI2C, i2cRegister, val);
return i2cWrite(SRF10_I2C_INSTANCE, SRF10_AddressI2C, i2cRegister, val);
}
static uint8_t i2c_srf10_read_byte(uint8_t i2cRegister)
{
uint8_t byte;
i2cRead(SRF10_AddressI2C, i2cRegister, 1, &byte);
i2cRead(SRF10_I2C_INSTANCE, SRF10_AddressI2C, i2cRegister, 1, &byte);
return byte;
}

View file

@ -15,15 +15,11 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "gpio.h"
#include "light_led.h"
#include "sound_beeper.h"
@ -35,12 +31,7 @@
#define EXTI_CALLBACK_HANDLER_COUNT 1
#endif
typedef struct extiCallbackHandlerConfig_s {
IRQn_Type irqn;
extiCallbackHandlerFunc* fn;
} extiCallbackHandlerConfig_t;
static extiCallbackHandlerConfig_t extiHandlerConfigs[EXTI_CALLBACK_HANDLER_COUNT];
extiCallbackHandlerConfig_t extiHandlerConfigs[EXTI_CALLBACK_HANDLER_COUNT];
void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
{
@ -55,48 +46,6 @@ void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
failureMode(FAILURE_DEVELOPER); // EXTI_CALLBACK_HANDLER_COUNT is too low for the amount of handlers required.
}
void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
{
for (int index = 0; index < EXTI_CALLBACK_HANDLER_COUNT; index++) {
extiCallbackHandlerConfig_t *candidate = &extiHandlerConfigs[index];
if (candidate->fn == fn && candidate->irqn == irqn) {
candidate->fn = NULL;
candidate->irqn = 0;
return;
}
}
}
static void extiHandler(IRQn_Type irqn)
{
for (int index = 0; index < EXTI_CALLBACK_HANDLER_COUNT; index++) {
extiCallbackHandlerConfig_t *candidate = &extiHandlerConfigs[index];
if (candidate->fn && candidate->irqn == irqn) {
candidate->fn();
}
}
}
void EXTI15_10_IRQHandler(void)
{
extiHandler(EXTI15_10_IRQn);
}
#if defined(CC3D) || defined(FURYF3)
void EXTI3_IRQHandler(void)
{
extiHandler(EXTI3_IRQn);
}
#endif
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
void EXTI9_5_IRQHandler(void)
{
extiHandler(EXTI9_5_IRQn);
}
#endif
// cycles per microsecond
static uint32_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
@ -104,7 +53,7 @@ static volatile uint32_t sysTickUptime = 0;
// cached value of RCC->CSR
uint32_t cachedRccCsrValue;
static void cycleCounterInit(void)
void cycleCounterInit(void)
{
RCC_ClocksTypeDef clocks;
RCC_GetClocksFreq(&clocks);
@ -124,7 +73,6 @@ uint32_t micros(void)
do {
ms = sysTickUptime;
cycle_cnt = SysTick->VAL;
/*
* If the SysTick timer expired during the previous instruction, we need to give it a little time for that
* interrupt to be delivered before we can recheck sysTickUptime:
@ -140,53 +88,6 @@ uint32_t millis(void)
return sysTickUptime;
}
void systemInit(void)
{
#ifdef CC3D
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
#endif
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
#ifdef STM32F10X
// Turn on clocks for stuff we use
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
#ifdef STM32F10X
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
digitalHi(GPIOA, gpio.pin);
gpioInit(GPIOA, &gpio);
// Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
#endif
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}
#if 1
void delayMicroseconds(uint32_t us)
{

View file

@ -24,25 +24,6 @@ void delay(uint32_t ms);
uint32_t micros(void);
uint32_t millis(void);
// failure
void failureMode(uint8_t mode);
// bootloader/IAP
void systemReset(void);
void systemResetToBootloader(void);
bool isMPUSoftReset(void);
void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz
extern uint32_t hse_value;
typedef void extiCallbackHandlerFunc(void);
void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
extern uint32_t cachedRccCsrValue;
typedef enum {
FAILURE_DEVELOPER = 0,
FAILURE_MISSING_ACC,
@ -53,3 +34,37 @@ typedef enum {
FAILURE_GYRO_INIT_FAILED
} failureMode_e;
// failure
void failureMode(failureMode_e mode);
// bootloader/IAP
void systemReset(void);
void systemResetToBootloader(void);
bool isMPUSoftReset(void);
void cycleCounterInit(void);
void checkForBootLoaderRequest(void);
void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz
extern uint32_t hse_value;
typedef void extiCallbackHandlerFunc(void);
typedef struct extiCallbackHandlerConfig_s {
IRQn_Type irqn;
extiCallbackHandlerFunc* fn;
} extiCallbackHandlerConfig_t;
#ifndef EXTI_CALLBACK_HANDLER_COUNT
#define EXTI_CALLBACK_HANDLER_COUNT 1
#endif
extern extiCallbackHandlerConfig_t extiHandlerConfigs[EXTI_CALLBACK_HANDLER_COUNT];
void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
extern uint32_t cachedRccCsrValue;

View file

@ -17,22 +17,27 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "gpio.h"
#include "nvic.h"
#include "system.h"
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
// from system_stm32f10x.c
void SetSysClock(bool overclock);
void systemReset(void)
{
// Generate system reset
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
}
void systemResetToBootloader(void) {
void systemResetToBootloader(void)
{
// 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC
@ -40,7 +45,6 @@ void systemResetToBootloader(void) {
systemReset();
}
void enableGPIOPowerUsageAndNoiseReductions(void)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC, ENABLE);
@ -61,3 +65,53 @@ bool isMPUSoftReset(void)
else
return false;
}
void systemInit(void)
{
checkForBootLoaderRequest();
SetSysClock(false);
#ifdef CC3D
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
#endif
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
// Turn on clocks for stuff we use
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
digitalHi(GPIOA, gpio.pin);
gpioInit(GPIOA, &gpio);
// Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}
void checkForBootLoaderRequest(void)
{
}

View file

@ -17,14 +17,16 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "gpio.h"
#include "nvic.h"
#include "system.h"
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
void SetSysClock();
void systemReset(void)
{
@ -32,7 +34,8 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
}
void systemResetToBootloader(void) {
void systemResetToBootloader(void)
{
// 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC
@ -76,3 +79,32 @@ bool isMPUSoftReset(void)
else
return false;
}
void systemInit(void)
{
checkForBootLoaderRequest();
// Enable FPU
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
SetSysClock();
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}
void checkForBootLoaderRequest(void)
{
}

View file

@ -88,9 +88,36 @@ static uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
#if USED_TIMERS & TIM_N(4)
_CASE(4);
#endif
#if USED_TIMERS & TIM_N(5)
_CASE(5);
#endif
#if USED_TIMERS & TIM_N(6)
_CASE(6);
#endif
#if USED_TIMERS & TIM_N(7)
_CASE(7);
#endif
#if USED_TIMERS & TIM_N(8)
_CASE(8);
#endif
#if USED_TIMERS & TIM_N(9)
_CASE(9);
#endif
#if USED_TIMERS & TIM_N(10)
_CASE(10);
#endif
#if USED_TIMERS & TIM_N(11)
_CASE(11);
#endif
#if USED_TIMERS & TIM_N(12)
_CASE(12);
#endif
#if USED_TIMERS & TIM_N(13)
_CASE(13);
#endif
#if USED_TIMERS & TIM_N(14)
_CASE(14);
#endif
#if USED_TIMERS & TIM_N(15)
_CASE(15);
#endif
@ -121,9 +148,36 @@ TIM_TypeDef * const usedTimers[USED_TIMER_COUNT] = {
#if USED_TIMERS & TIM_N(4)
_DEF(4),
#endif
#if USED_TIMERS & TIM_N(5)
_DEF(5),
#endif
#if USED_TIMERS & TIM_N(6)
_DEF(6),
#endif
#if USED_TIMERS & TIM_N(7)
_DEF(7),
#endif
#if USED_TIMERS & TIM_N(8)
_DEF(8),
#endif
#if USED_TIMERS & TIM_N(9)
_DEF(9),
#endif
#if USED_TIMERS & TIM_N(10)
_DEF(10),
#endif
#if USED_TIMERS & TIM_N(11)
_DEF(11),
#endif
#if USED_TIMERS & TIM_N(12)
_DEF(12),
#endif
#if USED_TIMERS & TIM_N(13)
_DEF(13),
#endif
#if USED_TIMERS & TIM_N(14)
_DEF(14),
#endif
#if USED_TIMERS & TIM_N(15)
_DEF(15),
#endif
@ -141,7 +195,7 @@ static inline uint8_t lookupChannelIndex(const uint16_t channel)
return channel >> 2;
}
static rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
{
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
@ -151,6 +205,18 @@ static rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
return 0;
}
#if defined(STM32F3) || defined(STM32F4)
uint8_t timerGPIOAF(TIM_TypeDef *tim)
{
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].alternateFunction;
}
}
return 0;
}
#endif
void timerNVICConfigure(uint8_t irq)
{
NVIC_InitTypeDef NVIC_InitStructure;
@ -171,7 +237,23 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
#if defined (STM32F40_41xxx)
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
#elif defined (STM32F411xE)
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
#else
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
#endif
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
@ -191,6 +273,16 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
timerNVICConfigure(TIM1_UP_IRQn);
break;
#endif
#if defined (STM32F40_41xxx) || defined(STM32F411xE)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
break;
#endif
#if defined (STM32F40_41xxx)
case TIM8_CC_IRQn:
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
break;
#endif
#ifdef STM32F303xC
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM16_IRQn);
@ -333,6 +425,13 @@ void timerChClearCCFlag(const timerHardware_t *timHw)
TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
}
// configure timer channel GPIO mode
void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode)
{
IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER, 0);
IOConfigGPIO(IOGetByTag(timHw->tag), mode);
}
// calculate input filter constant
// TODO - we should probably setup DTS to higher value to allow reasonable input filtering
// - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
@ -543,6 +642,13 @@ _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
# if defined(STM32F10X)
_TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
# endif
# if defined(STM32F40_41xxx) || defined (STM32F411xE)
# if USED_TIMERS & TIM_N(10)
_TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
# else
_TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
# endif
# endif
# ifdef STM32F303xC
# if USED_TIMERS & TIM_N(16)
_TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
@ -570,6 +676,15 @@ _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
# else // f10x_hd, f30x
_TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
# endif
# if defined(STM32F40_41xxx)
# if USED_TIMERS & TIM_N(13)
_TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
# else
_TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
# endif
# endif
# if defined (STM32F411xE)
# endif
#endif
#if USED_TIMERS & TIM_N(9)
_TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
@ -598,7 +713,7 @@ void timerInit(void)
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
#endif
// enable the timer peripherals
/* enable the timer peripherals */
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
}

View file

@ -69,6 +69,9 @@ typedef struct timerOvrHandlerRec_s {
typedef struct timerDef_s {
TIM_TypeDef *TIMx;
rccPeriphTag_t rcc;
#if defined(STM32F3) || defined(STM32F4)
uint8_t alternateFunction;
#endif
} timerDef_t;
typedef struct timerHardware_s {
@ -82,8 +85,11 @@ typedef struct timerHardware_s {
uint8_t alternateFunction;
#endif
} timerHardware_t;
enum {TIMER_OUTPUT_ENABLED = 0x01, TIMER_OUTPUT_INVERTED = 0x02};
enum {
TIMER_OUTPUT_ENABLED = 0x01,
TIMER_OUTPUT_INVERTED = 0x02
};
#ifdef STM32F1
#if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
@ -148,3 +154,8 @@ void timerForceOverflow(TIM_TypeDef *tim);
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
#if defined(STM32F3) || defined(STM32F4)
uint8_t timerGPIOAF(TIM_TypeDef *tim);
#endif

View file

@ -67,8 +67,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
tmp = (uint32_t) TIMx;
tmp += CCMR_Offset;
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
{
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
tmp += (TIM_Channel>>1);
/* Reset the OCxM bits in the CCMRx register */
@ -76,10 +75,8 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
}
else
{
tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1;
} else {
tmp += (uint16_t)(TIM_Channel - (uint16_t)4) >> (uint16_t)1;
/* Reset the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M);

View file

@ -10,16 +10,16 @@
#include "timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15) },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16) },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17) },
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_6 },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_1 },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_2 },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_10 },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_5 },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15), GPIO_AF_9 },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16), GPIO_AF_1 },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), GPIO_AF_1 },
};
@ -77,7 +77,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
/* Configure the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp |= TIM_OCMode;
} else {
tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1;
tmp += (uint32_t)(TIM_Channel - (uint32_t)4) >> (uint32_t)1;
/* Reset the OCxM bits in the CCMRx register */
*(__IO uint32_t *) tmp &= CCMR_OC24M_MASK;

View file

@ -234,15 +234,12 @@ void init(void)
memset(&pwm_params, 0, sizeof(pwm_params));
#ifdef SONAR
sonarGPIOConfig_t sonarGPIOConfig;
if (feature(FEATURE_SONAR)) {
const sonarHcsr04Hardware_t *sonarHardware = sonarGetHardwareConfiguration(masterConfig.batteryConfig.currentMeterType);
if (sonarHardware) {
sonarGPIOConfig.gpio = sonarHardware->echo_gpio;
sonarGPIOConfig.triggerPin = sonarHardware->echo_pin;
sonarGPIOConfig.echoPin = sonarHardware->trigger_pin;
pwm_params.sonarGPIOConfig = &sonarGPIOConfig;
pwm_params.useSonar = true;
pwm_params.sonarIOConfig.triggerTag = sonarHardware->triggerTag;
pwm_params.sonarIOConfig.echoTag = sonarHardware->echoTag;
}
}
#endif

View file

@ -60,6 +60,7 @@ STATIC_UNIT_TESTED uint16_t rxNrf24ReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig,
STATIC_UNIT_TESTED bool rxNrf24SetProtocol(nrf24_protocol_t protocol)
{
switch (protocol) {
default:
#ifdef USE_RX_V202
case NRF24RX_V202_250K:
case NRF24RX_V202_1M:
@ -98,9 +99,6 @@ STATIC_UNIT_TESTED bool rxNrf24SetProtocol(nrf24_protocol_t protocol)
protocolSetRcDataFromPayload = refSetRcDataFromPayload;
break;
#endif
default:
return false;
break;
}
return true;
}

View file

@ -72,7 +72,7 @@
#include "sensors/rangefinder.h"
#include "sensors/initialisation.h"
#ifdef NAZE
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
@ -91,101 +91,14 @@ uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE,
const extiConfig_t *selectMPUIntExtiConfig(void)
{
#ifdef NAZE
// MPU_INT output on rev4 PB13
static const extiConfig_t nazeRev4MPUIntExtiConfig = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB,
.gpioPin = Pin_13,
.gpioPort = GPIOB,
.exti_port_source = GPIO_PortSourceGPIOB,
.exti_line = EXTI_Line13,
.exti_pin_source = GPIO_PinSource13,
.exti_irqn = EXTI15_10_IRQn
};
// MPU_INT output on rev5 hardware PC13
static const extiConfig_t nazeRev5MPUIntExtiConfig = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC,
.gpioPin = Pin_13,
.gpioPort = GPIOC,
.exti_port_source = GPIO_PortSourceGPIOC,
.exti_line = EXTI_Line13,
.exti_pin_source = GPIO_PinSource13,
.exti_irqn = EXTI15_10_IRQn
};
if (hardwareRevision < NAZE32_REV5) {
return &nazeRev4MPUIntExtiConfig;
} else {
return &nazeRev5MPUIntExtiConfig;
}
#endif
#if defined(SPRACINGF3) || defined(SPRACINGF3EVO)
static const extiConfig_t spRacingF3MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPort = GPIOC,
.gpioPin = Pin_13,
.exti_port_source = EXTI_PortSourceGPIOC,
.exti_pin_source = EXTI_PinSource13,
.exti_line = EXTI_Line13,
.exti_irqn = EXTI15_10_IRQn
};
return &spRacingF3MPUIntExtiConfig;
#endif
#if defined(CC3D)
static const extiConfig_t cc3dMPUIntExtiConfig = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_3,
.exti_port_source = GPIO_PortSourceGPIOA,
.exti_pin_source = GPIO_PinSource3,
.exti_line = EXTI_Line3,
.exti_irqn = EXTI3_IRQn
};
return &cc3dMPUIntExtiConfig;
#endif
#ifdef MOTOLAB
static const extiConfig_t MotolabF3MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_15,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource15,
.exti_line = EXTI_Line15,
.exti_irqn = EXTI15_10_IRQn
};
return &MotolabF3MPUIntExtiConfig;
#endif
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
static const extiConfig_t colibriRaceMPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_5,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource5,
.exti_line = EXTI_Line5,
.exti_irqn = EXTI9_5_IRQn
};
return &colibriRaceMPUIntExtiConfig;
#endif
#if defined(FURYF3)
static const extiConfig_t FURYF3MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_3,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource3,
.exti_line = EXTI_Line3,
.exti_irqn = EXTI3_IRQn
};
return &FURYF3MPUIntExtiConfig;
#endif
#if defined(MPU_INT_EXTI)
static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) };
return &mpuIntExtiConfig;
#elif defined(USE_HARDWARE_REVISION_DETECTION)
return selectMPUIntExtiConfigByHardwareRevision();
#else
return NULL;
#endif
}
#ifdef USE_FAKE_GYRO
@ -206,11 +119,18 @@ static bool fakeGyroReadTemp(int16_t *tempData)
return true;
}
static bool fakeGyroInitStatus(void) {
return true;
}
bool fakeGyroDetect(gyro_t *gyro)
{
gyro->init = fakeGyroInit;
gyro->intStatus = fakeGyroInitStatus;
gyro->read = fakeGyroRead;
gyro->temperature = fakeGyroReadTemp;
gyro->scale = 1.0f / 16.4f;
return true;
}
#endif
@ -554,11 +474,8 @@ static void detectBaro(baroSensor_e baroHardwareToUse)
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
static const bmp085Config_t defaultBMP085Config = {
.gpioAPB2Peripherals = BARO_APB2_PERIPHERALS,
.xclrGpioPin = BARO_XCLR_PIN,
.xclrGpioPort = BARO_XCLR_GPIO,
.eocGpioPin = BARO_EOC_PIN,
.eocGpioPort = BARO_EOC_GPIO
.xclrIO = IO_TAG(BARO_XCLR_PIN),
.eocIO = IO_TAG(BARO_EOC_PIN),
};
bmp085Config = &defaultBMP085Config;
#endif
@ -628,27 +545,12 @@ static void detectMag(magSensor_e magHardwareToUse)
#ifdef USE_MAG_HMC5883
const hmc5883Config_t *hmc5883Config = 0;
#ifdef NAZE
#ifdef NAZE // TODO remove this target specific define
static const hmc5883Config_t nazeHmc5883Config_v1_v4 = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB,
.gpioPin = Pin_12,
.gpioPort = GPIOB,
/* Disabled for v4 needs more work.
.exti_port_source = GPIO_PortSourceGPIOB,
.exti_pin_source = GPIO_PinSource12,
.exti_line = EXTI_Line12,
.exti_irqn = EXTI15_10_IRQn
*/
.intTag = IO_TAG(PB12) /* perhaps disabled? */
};
static const hmc5883Config_t nazeHmc5883Config_v5 = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC,
.gpioPin = Pin_14,
.gpioPort = GPIOC,
.exti_port_source = GPIO_PortSourceGPIOC,
.exti_line = EXTI_Line14,
.exti_pin_source = GPIO_PinSource14,
.exti_irqn = EXTI15_10_IRQn
.intTag = IO_TAG(MAG_INT_EXTI)
};
if (hardwareRevision < NAZE32_REV5) {
hmc5883Config = &nazeHmc5883Config_v1_v4;
@ -657,18 +559,12 @@ static void detectMag(magSensor_e magHardwareToUse)
}
#endif
#ifdef SPRACINGF3
static const hmc5883Config_t spRacingF3Hmc5883Config = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPin = Pin_14,
.gpioPort = GPIOC,
.exti_port_source = EXTI_PortSourceGPIOC,
.exti_pin_source = EXTI_PinSource14,
.exti_line = EXTI_Line14,
.exti_irqn = EXTI15_10_IRQn
#ifdef MAG_INT_EXTI
static const hmc5883Config_t extiHmc5883Config = {
.intTag = IO_TAG(MAG_INT_EXTI)
};
hmc5883Config = &spRacingF3Hmc5883Config;
hmc5883Config = &extiHmc5883Config;
#endif
#endif
@ -820,9 +716,9 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t g
detectAcc(accHardwareToUse);
detectBaro(baroHardwareToUse);
// Now time to init things, acc first
if (sensors(SENSOR_ACC)) {
acc.acc_1G = 256; // set default
acc.init(&acc);
}

View file

@ -21,16 +21,17 @@
#include <math.h>
#include <platform.h>
#include "build_config.h"
#ifdef SONAR
#include "build_config.h"
#include "common/maths.h"
#include "config/config.h"
#include "config/runtime_config.h"
#include "drivers/gpio.h"
#include "drivers/io.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/sonar_srf10.h"
#include "drivers/rangefinder.h"
@ -67,34 +68,16 @@ static const sonarHcsr04Hardware_t *sonarGetHardwareConfigurationForHCSR04(curre
if (feature(FEATURE_SOFTSERIAL)
|| feature(FEATURE_RX_PARALLEL_PWM )
|| (feature(FEATURE_CURRENT_METER) && currentSensor == CURRENT_SENSOR_ADC)) {
sonarHcsr04Hardware = (sonarHcsr04Hardware_t){
.trigger_pin = SONAR_PWM_TRIGGER_PIN,
.trigger_gpio = SONAR_PWM_TRIGGER_GPIO,
.echo_pin = SONAR_PWM_ECHO_PIN,
.echo_gpio = SONAR_PWM_ECHO_GPIO,
.exti_line = SONAR_PWM_EXTI_LINE,
.exti_pin_source = SONAR_PWM_EXTI_PIN_SOURCE,
.exti_irqn = SONAR_PWM_EXTI_IRQN };
sonarHcsr04Hardware.triggerTag = IO_TAG(SONAR_TRIGGER_PIN_PWM);
sonarHcsr04Hardware.echoTag = IO_TAG(SONAR_ECHO_PIN_PWM);
} else {
sonarHcsr04Hardware = (sonarHcsr04Hardware_t){
.trigger_pin = SONAR_TRIGGER_PIN,
.trigger_gpio = SONAR_TRIGGER_GPIO,
.echo_pin = SONAR_ECHO_PIN,
.echo_gpio = SONAR_ECHO_GPIO,
.exti_line = SONAR_EXTI_LINE,
.exti_pin_source = SONAR_EXTI_PIN_SOURCE,
.exti_irqn = SONAR_EXTI_IRQN };
sonarHcsr04Hardware.triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
sonarHcsr04Hardware.echoTag = IO_TAG(SONAR_ECHO_PIN);
}
#elif defined(SONAR_TRIGGER_PIN)
UNUSED(currentSensor);
sonarHcsr04Hardware = (sonarHcsr04Hardware_t){
.trigger_pin = SONAR_TRIGGER_PIN,
.trigger_gpio = SONAR_TRIGGER_GPIO,
.echo_pin = SONAR_ECHO_PIN,
.echo_gpio = SONAR_ECHO_GPIO,
.exti_line = SONAR_EXTI_LINE,
.exti_pin_source = SONAR_EXTI_PIN_SOURCE,
.exti_irqn = SONAR_EXTI_IRQN };
sonarHcsr04Hardware.triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
sonarHcsr04Hardware.echoTag = IO_TAG(SONAR_ECHO_PIN);
#else
#error Sonar not defined for target
#endif

View file

@ -57,7 +57,6 @@ void updateHardwareRevision(void)
{
}
/* !!TODO - this has been deferred
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
{
// MPU_INT output on V1 PA15
@ -76,4 +75,3 @@ const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
return &alienFlightF3V2MPUIntExtiConfig;
}
}
*/

View file

@ -32,17 +32,18 @@
#define BEEPER PA5
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USE_EXTI
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
// Using MPU6050 for the moment.
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
// No baro support.
@ -52,8 +53,7 @@
// No mag support for now (option to use MPU9150 in the future).
//#define MAG
//#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW0_DEG_FLIP
//#define MAG_AK8975_ALIGN CW0_DEG_FLIP
#define USE_VCP
#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
@ -154,6 +154,6 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View file

@ -19,12 +19,24 @@
#define LED0 PB3
#define BEEPER PA15
#define BEEPER_OPT PB2
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_USART USART1
#define BEEPER PB15
#define BEEPER_OPT PB2
#define USE_EXTI
#define MPU_INT_EXTI PA3
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN GPIO_Pin_4
#define MPU6000_SPI_INSTANCE SPI1
@ -36,26 +48,19 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USABLE_TIMER_CHANNEL_COUNT 12
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
// External I2C BARO
#define BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_BARO_MS5611
// External I2C MAG
#define MAG
@ -73,13 +78,6 @@
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#if defined(CC3D_NRF24) || defined(CC3D_NRF24_OPBL)
#define USE_RX_NRF24
#endif
@ -88,7 +86,7 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
#define DEFAULT_FEATURES FEATURE_SOFTSPI
#define USE_RX_SYMA
#define USE_RX_V202
//#define USE_RX_V202
#define USE_RX_CX10
//#define USE_RX_H8_3D
#define USE_RX_REF
@ -100,6 +98,8 @@
#define USE_NRF24_SOFTSPI
// RC pinouts
// RC1 GND
// RC2 power
// RC3 PB6/TIM4 unused
// RC4 PB5/TIM3 SCK / softserial1 TX / sonar trigger
// RC5 PB0/TIM3 MISO / softserial1 RX / sonar echo / RSSI ADC
@ -128,6 +128,10 @@
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 4
#ifdef USE_UART1_RX_DMA
#undef USE_UART1_RX_DMA
#endif
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
@ -146,16 +150,6 @@
#define RSSI_ADC_PIN PB0
#endif
//#define SONAR
#define USE_SONAR_SRF10
#define SONAR_TRIGGER_PIN Pin_5 // (PB5)
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_0 // (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line0
#define SONAR_EXTI_PIN_SOURCE GPIO_PinSource0
#define SONAR_EXTI_IRQN EXTI0_IRQn
// LED strip is on PWM5 output pin
//#define LED_STRIP
#define LED_STRIP_TIMER TIM3
@ -167,6 +161,11 @@
//#define USE_SERIAL_4WAY_BLHELI_INTERFACE
//#define SONAR
#define USE_SONAR_SRF10
#define SONAR_ECHO_PIN PB0
#define SONAR_TRIGGER_PIN PB5
#define NAV
//#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION
@ -184,13 +183,12 @@
#ifdef USE_RX_NRF24
#undef USE_SERVOS
#define TARGET_MOTOR_COUNT 4
#undef USE_SONAR
#else
#define TARGET_MOTOR_COUNT 4
#undef USE_SONAR_SRF10
#endif // USE_RX_NRF24
#define TARGET_MOTOR_COUNT 4
#undef USE_MAG_AK8975
#undef USE_MAG_MAG3110
#undef BLACKBOX
@ -221,4 +219,5 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC ( BIT(14) )
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View file

@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "CHF3" // Chebuzz F3
@ -27,8 +26,6 @@
#define BEEPER PE9 // Red LEDs - PE9/PE13
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 18
#define USE_SPI
#define USE_SPI_DEVICE_1
@ -66,9 +63,6 @@
#define USE_USART2
#define SERIAL_PORT_COUNT 3
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PC0
@ -104,5 +98,6 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
#define USABLE_TIMER_CHANNEL_COUNT 18
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))

View file

@ -28,6 +28,7 @@
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/accgyro_spi_mpu6500.h"
#include "drivers/exti.h"
#include "hardware_revision.h"
@ -51,3 +52,8 @@ void detectHardwareRevision(void)
void updateHardwareRevision(void)
{
}
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
{
return NULL;
}

View file

@ -14,6 +14,7 @@
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0,
@ -27,3 +28,6 @@ void updateHardwareRevision(void);
void detectHardwareRevision(void);
void spiBusInit(void);
struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -72,9 +72,9 @@
#define USE_RX_V202
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_REF
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_CX10A
#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
#define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
#define SKIP_RX_PWM_PPM

View file

@ -26,6 +26,14 @@
#define BEEPER PB13
#define BEEPER_INVERTED
// MPU6500 interrupt
#define USE_EXTI
#define MPU_INT_EXTI PA5
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
#define MPU6500_CS_GPIO GPIOA
#define MPU6500_CS_PIN GPIO_Pin_4
@ -47,10 +55,6 @@
#define SPI1_MOSI_PIN GPIO_Pin_5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define USABLE_TIMER_CHANNEL_COUNT 11
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
@ -132,15 +136,13 @@
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
// MPU6500 interrupt
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define DEFAULT_FEATURES FEATURE_VBAT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
@ -148,5 +150,6 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View file

@ -19,6 +19,7 @@
#define TARGET_BOARD_IDENTIFIER "CPM1" // CrazePony MINI
#define BRUSHED_MOTORS
#define LED0 PA11
#define LED1 PA8
@ -36,17 +37,11 @@
#define MAG
#define USE_MAG_HMC5883
#define BRUSHED_MOTORS
#define USE_USART1
#define SERIAL_PORT_COUNT 1
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_GPIO GPIOB
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_8
#define VBAT_ADC_PIN PB0
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
@ -84,19 +79,9 @@
#undef USE_SERVOS
#define USE_QUAD_MIXER_ONLY
#if (FLASH_SIZE > 64)
#define BLACKBOX
#else
#define SKIP_TASK_STATISTICS
#define SKIP_CLI_COMMAND_HELP
#endif
// IO - assuming all IOs on 48pin package TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define USED_TIMERS TIM_N(2)
#define TIMER_APB1_PERIPHERALS RCC_APB1Periph_TIM2
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)

View file

@ -59,29 +59,18 @@
#define BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define SONAR
#define SONAR_PWM_TRIGGER_PIN Pin_8 // PWM5 (PB8) - 5v tolerant
#define SONAR_PWM_TRIGGER_GPIO GPIOB
#define SONAR_PWM_ECHO_PIN Pin_9 // PWM6 (PB9) - 5v tolerant
#define SONAR_PWM_ECHO_GPIO GPIOB
#define SONAR_PWM_EXTI_LINE EXTI_Line9
#define SONAR_PWM_EXTI_PIN_SOURCE GPIO_PinSource9
#define SONAR_PWM_EXTI_IRQN EXTI9_5_IRQn
#define SONAR_TRIGGER_PIN Pin_0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE GPIO_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN_PWM PB8
#define SONAR_ECHO_PIN_PWM PB9
#define USE_USART1
#define USE_USART2
@ -123,6 +112,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -24,9 +24,10 @@
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define MPU_INT_EXTI PC4
//#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU INT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -120,8 +121,6 @@
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
#endif
#define USABLE_TIMER_CHANNEL_COUNT 8
#define USB_IO
#define USE_VCP
@ -182,13 +181,9 @@
#define CURRENT_METER_ADC_PIN PA2
#define SONAR
#define SONAR_TRIGGER_PIN Pin_0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE EXTI_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
@ -224,11 +219,9 @@
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 8
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View file

@ -18,7 +18,6 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "LUX"
#define BOARD_HAS_VOLTAGE_DIVIDER
#define LED0 PC15
#define LED1 PC14
@ -27,6 +26,14 @@
#define BEEPER PB13
#define BEEPER_INVERTED
// MPU6500 interrupt
#define USE_EXTI
#define MPU_INT_EXTI PA5
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
#define MPU6500_CS_GPIO GPIOA
#define MPU6500_CS_PIN GPIO_Pin_4
@ -44,10 +51,6 @@
#define SPI1_MOSI_PIN GPIO_Pin_5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define USABLE_TIMER_CHANNEL_COUNT 11
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
@ -87,6 +90,7 @@
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC1
#define VBAT_ADC_PIN PC0
@ -110,11 +114,6 @@
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
// MPU6500 interrupt
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define SPEKTRUM_BIND
// USART1, PC5
#define BIND_PORT GPIOC
@ -135,5 +134,6 @@
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View file

@ -25,21 +25,19 @@
#define BEEPER PA0
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW180_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
//#define BARO
@ -168,5 +166,6 @@
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -26,6 +26,7 @@
#include "drivers/system.h"
#include "drivers/bus_spi.h"
#include "drivers/sensor.h"
#include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/accgyro.h"
#include "drivers/accgyro_mpu.h"
@ -103,3 +104,27 @@ void updateHardwareRevision(void)
hardwareRevision = NAZE32_SP;
#endif
}
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
{
// MPU_INT output on rev5 hardware PC13
static const extiConfig_t nazeRev5MPUIntExtiConfig = {
.tag = IO_TAG(PC13)
};
#ifdef AFROMINI
return &nazeRev5MPUIntExtiConfig;
#else
// MPU_INT output on rev4 PB13
static const extiConfig_t nazeRev4MPUIntExtiConfig = {
.tag = IO_TAG(PB13)
};
if (hardwareRevision < NAZE32_REV5) {
return &nazeRev4MPUIntExtiConfig;
}
else {
return &nazeRev5MPUIntExtiConfig;
}
#endif
}

View file

@ -14,6 +14,7 @@
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum nazeHardwareRevision_t {
UNKNOWN = 0,
@ -28,3 +29,6 @@ void updateHardwareRevision(void);
void detectHardwareRevision(void);
void spiBusInit(void);
struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -30,14 +30,20 @@
#define BEEPER_INVERTED
#endif
#define BARO_XCLR_PIN PC13
#define BARO_EOC_PIN PC14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define BARO_XCLR_GPIO GPIOC
#define BARO_XCLR_PIN Pin_13
#define BARO_EOC_GPIO GPIOC
#define BARO_EOC_PIN Pin_14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define USE_EXTI
#define MAG_INT_EXTI PC14
#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MAG_DATA_READY_INTERRUPT
#define USE_MAG_DATA_READY_SIGNAL
// SPI2
// PB15 28 SPI2_MOSI
@ -63,34 +69,23 @@
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MAG_DATA_READY_INTERRUPT
#define USE_MAG_DATA_READY_SIGNAL
#define GYRO
#define USE_GYRO_MPU3050
#define USE_GYRO_MPU6050
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU3050_ALIGN CW0_DEG
#define GYRO_MPU6050_ALIGN CW0_DEG
#define GYRO_MPU6500_ALIGN CW0_DEG
#define ACC
#define USE_ACC_ADXL345
//#define USE_ACC_BMA280
//#define USE_ACC_MMA8452
#define USE_ACC_BMA280
#define USE_ACC_MMA8452
#define USE_ACC_MPU6050
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
@ -110,25 +105,14 @@
#define USE_MAG_HMC5883
//#define USE_MAG_AK8975
//#define USE_MAG_MAG3110
#define MAG_HMC5883_ALIGN CW180_DEG
#define SONAR
//#define USE_SONAR_SRF10
#define SONAR_PWM_TRIGGER_PIN Pin_8 // PWM5 (PB8) - 5v tolerant
#define SONAR_PWM_TRIGGER_GPIO GPIOB
#define SONAR_PWM_ECHO_PIN Pin_9 // PWM6 (PB9) - 5v tolerant
#define SONAR_PWM_ECHO_GPIO GPIOB
#define SONAR_PWM_EXTI_LINE EXTI_Line9
#define SONAR_PWM_EXTI_PIN_SOURCE GPIO_PinSource9
#define SONAR_PWM_EXTI_IRQN EXTI9_5_IRQn
#define SONAR_TRIGGER_PIN Pin_0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE GPIO_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN_PWM PB8
#define SONAR_ECHO_PIN_PWM PB9
#define USE_USART1
#define USE_USART2
@ -154,27 +138,37 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
//#define USE_RX_NRF24
#ifdef USE_RX_NRF24
#define USE_RX_SYMA
//#define USE_RX_V202
#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
#define USE_SOFTSPI
#define USE_NRF24_SOFTSPI
// #define SOFT_I2C // enable to test software i2c
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
// #define SOFT_I2C_PB67
#define USE_RX_NRF24
#ifdef USE_RX_NRF24
#define USE_RX_CX10
#define USE_RX_H8_3D
//#define USE_RX_REF
#define USE_RX_SYMA
//#define USE_RX_V202
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_REF
#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_CX10A
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
#define USE_SOFTSPI
#define USE_NRF24_SOFTSPI
// RC pinouts
// RC3 RX_PPM
// RC4 PA1 CE / RSSI_ADC
// RC5 PA2 USART2 TX
// RC6 PA3 USART2 RX
// RC1 GND
// RC2 power
// RC3 PA0/TIM2 RX_PPM
// RC4 PA1/TIM2 CE / RSSI_ADC
// RC5 PA2/TIM2 USART2 TX
// RC6 PA3/TIM2 USART2 RX
// RC7 PA6/TIM3 CSN / softserial1 RX / LED_STRIP
// RC8 PA7 SCK / softserial1 TX
// RC9 PB0 MISO / softserial2 RX / sonar trigger
// RC10 PB1 MOSI /softserial2 TX / sonar echo / current
// RC8 PA7/TIM3 SCK / softserial1 TX
// RC9 PB0/TIM3 MISO / softserial2 RX / sonar trigger
// RC10 PB1/TIM3 MOSI /softserial2 TX / sonar echo / current
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
#define NRF24_CE_GPIO GPIOA
@ -202,7 +196,7 @@
#define NAV_GPS_GLITCH_DETECTION
#define NAV_MAX_WAYPOINTS 30
#define LED_STRIP
//#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define SPEKTRUM_BIND
@ -214,6 +208,7 @@
#define TARGET_MOTOR_COUNT 6
#define DISABLE_UNCOMMON_MIXERS
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
// alternative defaults for ALIENFLIGHTF1 F1 target
#ifdef ALIENFLIGHTF1
@ -224,7 +219,7 @@
#undef SONAR
#undef TARGET_MOTOR_COUNT
#define TARGET_MOTOR_COUNT 6
#define TARGET_MOTOR_COUNT 8
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL

View file

@ -53,18 +53,14 @@
#define BARO
//#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define MAG
#define USE_MAG_HMC5883
#define SONAR
#define SONAR_TRIGGER_PIN Pin_0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE GPIO_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_PIN PB1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define USE_USART1
#define USE_USART2
@ -101,5 +97,4 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -28,10 +28,8 @@
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define BARO_XCLR_GPIO GPIOC
#define BARO_XCLR_PIN Pin_13
#define BARO_EOC_GPIO GPIOC
#define BARO_EOC_PIN Pin_14
#define BARO_XCLR_PIN PC13
#define BARO_EOC_PIN PC14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define USE_SPI
@ -76,6 +74,7 @@
#define BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define MAG
#define USE_MAG_HMC5883
@ -86,20 +85,10 @@
#define USE_FLASH_M25P16
#define SONAR
#define SONAR_PWM_TRIGGER_PIN Pin_8 // PWM5 (PB8) - 5v tolerant
#define SONAR_PWM_TRIGGER_GPIO GPIOB
#define SONAR_PWM_ECHO_PIN Pin_9 // PWM6 (PB9) - 5v tolerant
#define SONAR_PWM_ECHO_GPIO GPIOB
#define SONAR_PWM_EXTI_LINE EXTI_Line9
#define SONAR_PWM_EXTI_PIN_SOURCE GPIO_PinSource9
#define SONAR_PWM_EXTI_IRQN EXTI9_5_IRQn
#define SONAR_TRIGGER_PIN Pin_0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE GPIO_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0 // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_PIN PB1 // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_PIN_PWM PB8 // PWM5 (PB8) - 5v tolerant
#define SONAR_ECHO_PIN_PWM PB9 // PWM6 (PB9) - 5v tolerant
#define USE_USART1
#define USE_USART2
@ -138,7 +127,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -24,17 +24,13 @@
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_EXTI
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
@ -55,14 +51,8 @@
#define USE_FLASH_M25P16
#define SONAR
#define SONAR_TRIGGER_PIN Pin_0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE EXTI_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define USE_USART1
#define USE_USART2
@ -168,5 +158,5 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View file

@ -25,17 +25,13 @@
#define BEEPER PA1
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 11
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define BARO
@ -45,7 +41,6 @@
#define USE_MAG_HMC5883
#define USE_MAG_AK8975
#define USE_MAG_MAG3110
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define USE_VCP
@ -102,13 +97,8 @@
#define NAV_MAX_WAYPOINTS 60
#define SONAR
#define SONAR_TRIGGER_PIN Pin_2 // PWM6 (PA2) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOA
#define SONAR_ECHO_PIN Pin_1 // PWM7 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE EXTI_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PA2 // PWM6 (PA2) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_PIN PB1 // PWM7 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define LED_STRIP
#if 1
@ -161,7 +151,6 @@
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View file

@ -24,16 +24,12 @@
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
@ -57,13 +53,8 @@
#define USE_FLASH_M25P16
#define SONAR
#define SONAR_TRIGGER_PIN Pin_0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_TRIGGER_GPIO GPIOB
#define SONAR_ECHO_PIN Pin_1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
#define SONAR_ECHO_GPIO GPIOB
#define SONAR_EXTI_LINE EXTI_Line1
#define SONAR_EXTI_PIN_SOURCE EXTI_PinSource1
#define SONAR_EXTI_IRQN EXTI1_IRQn
#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1
#define USE_USART1
#define USE_USART2
@ -166,6 +157,6 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View file

@ -29,6 +29,7 @@
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define GYRO
#define USE_GYRO_L3GD20
@ -74,6 +75,5 @@
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0x00ff
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))

View file

@ -15,15 +15,20 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define USE_SERVOS
#define USE_CLI
#define SERIAL_RX
#define BLACKBOX
#define I2C1_OVERCLOCK false
#define I2C2_OVERCLOCK false
#if (FLASH_SIZE > 64)
#define USE_SERVOS
#define SERIAL_RX
#define USE_CLI
#if (FLASH_SIZE <= 64)
#define SKIP_TASK_STATISTICS
#define SKIP_CLI_COMMAND_HELP
#else
#define BLACKBOX
#define GPS
#define GPS_PROTO_NMEA
#define GPS_PROTO_UBLOX