Configurable I2C (rework)

This commit is contained in:
jflyper 2017-06-05 22:46:26 +09:00
parent a72f98e4f3
commit 52bfef1ea5
39 changed files with 1195 additions and 384 deletions

View File

@ -134,6 +134,8 @@ GROUP_2_TARGETS := \
FF_PIKOBLX \
FF_PIKOF4 \
FF_RADIANCE \
FRSKYF3 \
FRSKYF4 \
FURYF3 \
FURYF4 \
FURYF7 \
@ -675,6 +677,7 @@ COMMON_SRC = \
config/config_streamer.c \
drivers/adc.c \
drivers/buf_writer.c \
drivers/bus_i2c_config.c \
drivers/bus_i2c_soft.c \
drivers/bus_spi.c \
drivers/bus_spi_soft.c \
@ -892,7 +895,11 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
io/osd_slave.c
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
drivers/bus_i2c_config.c \
drivers/serial_escserial.c \
drivers/serial_pinconfig.c \
drivers/serial_uart_init.c \
drivers/serial_uart_pinconfig.c \
drivers/vtx_rtc6705_soft_spi.c \
drivers/vtx_rtc6705.c \
drivers/vtx_common.c \
@ -903,9 +910,6 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
config/feature.c \
config/parameter_group.c \
config/config_streamer.c \
drivers/serial_pinconfig.c \
drivers/serial_uart_init.c \
drivers/serial_uart_pinconfig.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
@ -1019,6 +1023,7 @@ SITLEXCLUDES = \
drivers/adc.c \
drivers/bus_spi.c \
drivers/bus_i2c.c \
drivers/bus_i2c_config.c \
drivers/dma.c \
drivers/pwm_output.c \
drivers/timer.c \

View File

@ -106,7 +106,8 @@
#define PG_VTX_CONFIG 515
#define PG_SONAR_CONFIG 516
#define PG_ESC_SENSOR_CONFIG 517
#define PG_BETAFLIGHT_END 517
#define PG_I2C_CONFIG 518
#define PG_BETAFLIGHT_END 518
// OSD configuration (subject to change)

View File

@ -15,34 +15,10 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#pragma once
#include "platform.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "hardware_revision.h"
void targetBusInit(void)
{
#ifdef USE_SPI
#ifdef USE_SPI_DEVICE_1
spiInit(SPIDEV_1);
#ifdef TARGET_BUS_INIT
void targetBusInit(void);
#endif
#ifdef USE_SPI_DEVICE_2
spiInit(SPIDEV_2);
#endif
#ifdef USE_SPI_DEVICE_3
if (hardwareRevision == AFF3_REV_2) {
spiInit(SPIDEV_3);
}
#endif
#ifdef USE_SPI_DEVICE_4
spiInit(SPIDEV_4);
#endif
#endif
#ifdef USE_I2C
i2cInit(I2C_DEVICE);
#endif
}

View File

@ -19,14 +19,10 @@
#include "platform.h"
#include "config/parameter_group.h"
#include "drivers/io_types.h"
#include "drivers/rcc_types.h"
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID
#endif
@ -36,39 +32,27 @@ typedef enum I2CDevice {
I2CDEV_1 = 0,
I2CDEV_2,
I2CDEV_3,
#ifdef USE_I2C_DEVICE_4
I2CDEV_4,
#endif
I2CDEV_COUNT
} I2CDevice;
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;
#if defined(STM32F1) || defined(STM32F3)
#define I2CDEV_COUNT 2
#elif defined(STM32F4)
#define I2CDEV_COUNT 3
#elif defined(STM32F7)
#define I2CDEV_COUNT 4
#else
#define I2CDEV_COUNT 4
#endif
#if defined(STM32F7)
uint8_t af;
#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;
typedef struct i2cConfig_s {
ioTag_t ioTagScl[I2CDEV_COUNT];
ioTag_t ioTagSda[I2CDEV_COUNT];
bool overClock[I2CDEV_COUNT];
bool pullUp[I2CDEV_COUNT];
} i2cConfig_t;
void i2cHardwareConfigure(void);
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);

View File

@ -0,0 +1,262 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Created by jflyper
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "drivers/io.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_impl.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#if defined(USE_I2C) && !defined(SOFT_I2C)
#ifdef I2C_FULL_RECONFIGURABILITY
#if I2CDEV_COUNT >= 1
#ifndef I2C1_SCL
#define I2C1_SCL NONE
#endif
#ifndef I2C1_SDA
#define I2C1_SDA NONE
#endif
#endif
#if I2CDEV_COUNT >= 2
#ifndef I2C2_SCL
#define I2C2_SCL NONE
#endif
#ifndef I2C2_SDA
#define I2C2_SDA NONE
#endif
#endif
#if I2CDEV_COUNT >= 3
#ifndef I2C3_SCL
#define I2C3_SCL NONE
#endif
#ifndef I2C3_SDA
#define I2C3_SDA NONE
#endif
#endif
#if I2CDEV_COUNT >= 4
#ifndef I2C4_SCL
#define I2C4_SCL NONE
#endif
#ifndef I2C4_SDA
#define I2C4_SDA NONE
#endif
#endif
#else // I2C_FULL_RECONFIGURABILITY
// Backward compatibility for exisiting targets
#ifdef STM32F1
#ifndef I2C1_SCL
#define I2C1_SCL PB8
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB9
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
#endif // STM32F1
#ifdef STM32F3
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PA9
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PA10
#endif
#endif // STM32F3
#ifdef STM32F4
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
#ifndef I2C3_SCL
#define I2C3_SCL PA8
#endif
#ifndef I2C3_SDA
#define I2C3_SDA PC9
#endif
#endif // STM32F4
#ifdef STM32F7
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
#ifndef I2C3_SCL
#define I2C3_SCL PA8
#endif
#ifndef I2C3_SDA
#define I2C3_SDA PB4
#endif
#ifndef I2C4_SCL
#define I2C4_SCL PD12
#endif
#ifndef I2C4_SDA
#define I2C4_SDA PD13
#endif
#endif // STM32F7
#endif // I2C_FULL_RECONFIGURABILITY
// Backward compatibility for overclocking and internal pullup.
// These will eventually be configurable through PG-based configurator
// (and/or probably through some cli extension).
#ifndef I2C1_OVERCLOCK
#define I2C1_OVERCLOCK false
#endif
#ifndef I2C2_OVERCLOCK
#define I2C2_OVERCLOCK false
#endif
#ifndef I2C3_OVERCLOCK
#define I2C3_OVERCLOCK false
#endif
#ifndef I2C4_OVERCLOCK
#define I2C4_OVERCLOCK false
#endif
// Default values for internal pullup
#if defined(USE_I2C_PULLUP)
#define I2C1_PULLUP true
#define I2C2_PULLUP true
#define I2C3_PULLUP true
#define I2C4_PULLUP true
#else
#define I2C1_PULLUP false
#define I2C2_PULLUP false
#define I2C3_PULLUP false
#define I2C4_PULLUP false
#endif
typedef struct i2cDefaultConfig_s {
I2CDevice device;
ioTag_t ioTagScl, ioTagSda;
bool overClock;
bool pullUp;
} i2cDefaultConfig_t;
static const i2cDefaultConfig_t i2cDefaultConfig[] = {
#ifdef USE_I2C_DEVICE_1
{ I2CDEV_1, IO_TAG(I2C1_SCL), IO_TAG(I2C1_SDA), I2C1_OVERCLOCK, I2C1_PULLUP },
#endif
#ifdef USE_I2C_DEVICE_2
{ I2CDEV_2, IO_TAG(I2C2_SCL), IO_TAG(I2C2_SDA), I2C2_OVERCLOCK, I2C2_PULLUP },
#endif
#ifdef USE_I2C_DEVICE_3
{ I2CDEV_3, IO_TAG(I2C3_SCL), IO_TAG(I2C3_SDA), I2C3_OVERCLOCK, I2C3_PULLUP },
#endif
#ifdef USE_I2C_DEVICE_4
{ I2CDEV_4, IO_TAG(I2C4_SCL), IO_TAG(I2C4_SDA), I2C4_OVERCLOCK, I2C4_PULLUP },
#endif
};
PG_DECLARE(i2cConfig_t, i2cConfig);
PG_REGISTER_WITH_RESET_FN(i2cConfig_t, i2cConfig, PG_I2C_CONFIG, 0);
void pgResetFn_i2cConfig(i2cConfig_t *i2cConfig)
{
memset(i2cConfig, 0, sizeof(*i2cConfig));
for (size_t index = 0 ; index < ARRAYLEN(i2cDefaultConfig) ; index++) {
const i2cDefaultConfig_t *defconf = &i2cDefaultConfig[index];
i2cConfig->ioTagScl[defconf->device] = defconf->ioTagScl;
i2cConfig->ioTagSda[defconf->device] = defconf->ioTagSda;
i2cConfig->overClock[defconf->device] = defconf->overClock;
i2cConfig->pullUp[defconf->device] = defconf->pullUp;
}
}
void i2cHardwareConfigure(void)
{
const i2cConfig_t *pConfig = i2cConfig();
for (int index = 0 ; index < I2CDEV_COUNT ; index++) {
const i2cHardware_t *hardware = &i2cHardware[index];
if (!hardware->reg) {
continue;
}
I2CDevice device = hardware->device;
i2cDevice_t *pDev = &i2cDevice[device];
memset(pDev, 0, sizeof(*pDev));
for (int pindex = 0 ; pindex < I2C_PIN_SEL_MAX ; pindex++) {
if (pConfig->ioTagScl[device] == hardware->sclPins[pindex])
pDev->scl = IOGetByTag(pConfig->ioTagScl[device]);
if (pConfig->ioTagSda[device] == hardware->sdaPins[pindex])
pDev->sda = IOGetByTag(pConfig->ioTagSda[device]);
}
if (pDev->scl && pDev->sda) {
pDev->hardware = hardware;
pDev->reg = hardware->reg;
pDev->overClock = pConfig->overClock[device];
pDev->pullUp = pConfig->pullUp[device];
}
}
}
#endif // defined(USE_I2C) && !defined(USE_SOFT_I2C)

View File

@ -17,114 +17,118 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <platform.h>
#include "drivers/bus_i2c.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/nvic.h"
#include "drivers/time.h"
#include "drivers/rcc.h"
#include "io_impl.h"
#include "rcc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_impl.h"
#if !defined(SOFT_I2C) && defined(USE_I2C)
#if defined(USE_I2C) && !defined(SOFT_I2C)
#define CLOCKSPEED 800000 // i2c clockspeed 400kHz default (conform specs), 800kHz and 1200kHz (Betaflight default)
static void i2cUnstick(IO_t scl, IO_t sda);
#if defined(USE_I2C_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#else
#define IOCFG_I2C IOCFG_AF_OD
#endif
#define IOCFG_I2C_PU IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#define GPIO_AF4_I2C GPIO_AF4_I2C1
#ifndef I2C1_SDA
#define I2C1_SDA PB7
const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#ifdef USE_I2C_DEVICE_1
{
.device = I2CDEV_1,
.reg = I2C1,
.sclPins = { DEFIO_TAG_E(PB6), DEFIO_TAG_E(PB8) },
.sdaPins = { DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB9) },
.rcc = RCC_APB1(I2C1),
.ev_irq = I2C1_EV_IRQn,
.er_irq = I2C1_ER_IRQn,
},
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#ifdef USE_I2C_DEVICE_2
{
.device = I2CDEV_2,
.reg = I2C2,
.sclPins = { DEFIO_TAG_E(PB10), DEFIO_TAG_E(PF1) },
.sdaPins = { DEFIO_TAG_E(PB11), DEFIO_TAG_E(PF0) },
.rcc = RCC_APB1(I2C2),
.ev_irq = I2C2_EV_IRQn,
.er_irq = I2C2_ER_IRQn,
},
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#ifdef USE_I2C_DEVICE_3
{
.device = I2CDEV_3,
.reg = I2C3,
.sclPins = { DEFIO_TAG_E(PA8) },
.sdaPins = { DEFIO_TAG_E(PC9) },
.rcc = RCC_APB1(I2C3),
.ev_irq = I2C3_EV_IRQn,
.er_irq = I2C3_ER_IRQn,
},
#endif
#ifndef I2C3_SCL
#define I2C3_SCL PA8
#endif
#ifndef I2C3_SDA
#define I2C3_SDA PB4
#endif
#if defined(USE_I2C_DEVICE_4)
#ifndef I2C4_SCL
#define I2C4_SCL PD12
#endif
#ifndef I2C4_SDA
#define I2C4_SDA PD13
#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, .af = GPIO_AF4_I2C1 },
{ .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, .af = GPIO_AF4_I2C2 },
{ .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, .af = GPIO_AF4_I2C3 },
#if defined(USE_I2C_DEVICE_4)
{ .dev = I2C4, .scl = IO_TAG(I2C4_SCL), .sda = IO_TAG(I2C4_SDA), .rcc = RCC_APB1(I2C4), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C4_EV_IRQn, .er_irq = I2C4_ER_IRQn, .af = GPIO_AF4_I2C4 }
#ifdef USE_I2C_DEVICE_4
{
.device = I2CDEV_4,
.reg = I2C4,
.sclPins = { DEFIO_TAG_E(PD12), DEFIO_TAG_E(PF14) },
.sdaPins = { DEFIO_TAG_E(PD13), DEFIO_TAG_E(PF15) },
.rcc = RCC_APB1(I2C4),
.ev_irq = I2C4_EV_IRQn,
.er_irq = I2C4_ER_IRQn,
},
#endif
};
typedef struct{
I2C_HandleTypeDef Handle;
}i2cHandle_t;
static i2cHandle_t i2cHandle[I2CDEV_COUNT];
i2cDevice_t i2cDevice[I2CDEV_COUNT];
void I2C1_ER_IRQHandler(void)
{
HAL_I2C_ER_IRQHandler(&i2cHandle[I2CDEV_1].Handle);
HAL_I2C_ER_IRQHandler(&i2cDevice[I2CDEV_1].handle);
}
void I2C1_EV_IRQHandler(void)
{
HAL_I2C_EV_IRQHandler(&i2cHandle[I2CDEV_1].Handle);
HAL_I2C_EV_IRQHandler(&i2cDevice[I2CDEV_1].handle);
}
void I2C2_ER_IRQHandler(void)
{
HAL_I2C_ER_IRQHandler(&i2cHandle[I2CDEV_2].Handle);
HAL_I2C_ER_IRQHandler(&i2cDevice[I2CDEV_2].handle);
}
void I2C2_EV_IRQHandler(void)
{
HAL_I2C_EV_IRQHandler(&i2cHandle[I2CDEV_2].Handle);
HAL_I2C_EV_IRQHandler(&i2cDevice[I2CDEV_2].handle);
}
void I2C3_ER_IRQHandler(void)
{
HAL_I2C_ER_IRQHandler(&i2cHandle[I2CDEV_3].Handle);
HAL_I2C_ER_IRQHandler(&i2cDevice[I2CDEV_3].handle);
}
void I2C3_EV_IRQHandler(void)
{
HAL_I2C_EV_IRQHandler(&i2cHandle[I2CDEV_3].Handle);
HAL_I2C_EV_IRQHandler(&i2cDevice[I2CDEV_3].handle);
}
#ifdef USE_I2C_DEVICE_4
void I2C4_ER_IRQHandler(void)
{
HAL_I2C_ER_IRQHandler(&i2cHandle[I2CDEV_4].Handle);
HAL_I2C_ER_IRQHandler(&i2cDevice[I2CDEV_4].handle);
}
void I2C4_EV_IRQHandler(void)
{
HAL_I2C_EV_IRQHandler(&i2cHandle[I2CDEV_4].Handle);
HAL_I2C_EV_IRQHandler(&i2cDevice[I2CDEV_4].handle);
}
#endif
@ -147,12 +151,22 @@ static bool i2cHandleHardwareFailure(I2CDevice device)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return false;
}
I2C_HandleTypeDef *pHandle = &i2cDevice[device].handle;
if (!pHandle->Instance) {
return false;
}
HAL_StatusTypeDef status;
if(reg_ == 0xFF)
status = HAL_I2C_Master_Transmit(&i2cHandle[device].Handle,addr_ << 1,data, len_, I2C_DEFAULT_TIMEOUT);
status = HAL_I2C_Master_Transmit(pHandle ,addr_ << 1, data, len_, I2C_DEFAULT_TIMEOUT);
else
status = HAL_I2C_Mem_Write(&i2cHandle[device].Handle,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,data, len_, I2C_DEFAULT_TIMEOUT);
status = HAL_I2C_Mem_Write(pHandle ,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,data, len_, I2C_DEFAULT_TIMEOUT);
if(status != HAL_OK)
return i2cHandleHardwareFailure(device);
@ -167,12 +181,22 @@ 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)
{
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return false;
}
I2C_HandleTypeDef *pHandle = &i2cDevice[device].handle;
if (!pHandle->Instance) {
return false;
}
HAL_StatusTypeDef status;
if(reg_ == 0xFF)
status = HAL_I2C_Master_Receive(&i2cHandle[device].Handle,addr_ << 1,buf, len, I2C_DEFAULT_TIMEOUT);
status = HAL_I2C_Master_Receive(pHandle ,addr_ << 1, buf, len, I2C_DEFAULT_TIMEOUT);
else
status = HAL_I2C_Mem_Read(&i2cHandle[device].Handle,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,buf, len, I2C_DEFAULT_TIMEOUT);
status = HAL_I2C_Mem_Read(pHandle, addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,buf, len, I2C_DEFAULT_TIMEOUT);
if(status != HAL_OK)
return i2cHandleHardwareFailure(device);
@ -182,87 +206,72 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
void i2cInit(I2CDevice device)
{
/*## Configure the I2C clock source. The clock is derived from the SYSCLK #*/
// RCC_PeriphCLKInitTypeDef RCC_PeriphCLKInitStruct;
// RCC_PeriphCLKInitStruct.PeriphClockSelection = i2cHardwareMap[device].clk;
// RCC_PeriphCLKInitStruct.I2c1ClockSelection = i2cHardwareMap[device].clk_src;
// HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphCLKInitStruct);
switch (device) {
case I2CDEV_1:
__HAL_RCC_I2C1_CLK_ENABLE();
break;
case I2CDEV_2:
__HAL_RCC_I2C2_CLK_ENABLE();
break;
case I2CDEV_3:
__HAL_RCC_I2C3_CLK_ENABLE();
break;
#ifdef USE_I2C_DEVICE_4
case I2CDEV_4:
__HAL_RCC_I2C4_CLK_ENABLE();
break;
#endif
default:
break;
}
if (device == I2CINVALID)
if (device == I2CINVALID) {
return;
}
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
i2cDevice_t *pDev = &i2cDevice[device];
//I2C_InitTypeDef i2cInit;
const i2cHardware_t *hardware = pDev->hardware;
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
if (!hardware) {
return;
}
IO_t scl = pDev->scl;
IO_t sda = pDev->sda;
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
// Enable RCC
RCC_ClockCmd(i2c->rcc, ENABLE);
RCC_ClockCmd(hardware->rcc, ENABLE);
i2cUnstick(scl, sda);
// Init pins
#ifdef STM32F7
IOConfigGPIOAF(scl, IOCFG_I2C, i2c->af);
IOConfigGPIOAF(sda, IOCFG_I2C, i2c->af);
IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF4_I2C);
IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF4_I2C);
#else
IOConfigGPIO(scl, IOCFG_AF_OD);
IOConfigGPIO(sda, IOCFG_AF_OD);
#endif
// Init I2C peripheral
i2cHandle[device].Handle.Instance = i2cHardwareMap[device].dev;
I2C_HandleTypeDef *pHandle = &pDev->handle;
memset(pHandle, 0, sizeof(*pHandle));
pHandle->Instance = pDev->hardware->reg;
/// TODO: HAL check if I2C timing is correct
if (i2c->overClock) {
if (pDev->overClock) {
// 800khz Maximum speed tested on various boards without issues
i2cHandle[device].Handle.Init.Timing = 0x00500D1D;
pHandle->Init.Timing = 0x00500D1D;
} else {
//i2cHandle[device].Handle.Init.Timing = 0x00500B6A;
i2cHandle[device].Handle.Init.Timing = 0x00500C6F;
pHandle->Init.Timing = 0x00500C6F;
}
//i2cHandle[device].Handle.Init.Timing = 0x00D00E28; /* (Rise time = 120ns, Fall time = 25ns) */
i2cHandle[device].Handle.Init.OwnAddress1 = 0x0;
i2cHandle[device].Handle.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
i2cHandle[device].Handle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
i2cHandle[device].Handle.Init.OwnAddress2 = 0x0;
i2cHandle[device].Handle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
i2cHandle[device].Handle.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
pHandle->Init.OwnAddress1 = 0x0;
pHandle->Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
pHandle->Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
pHandle->Init.OwnAddress2 = 0x0;
pHandle->Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
pHandle->Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
HAL_I2C_Init(&i2cHandle[device].Handle);
/* Enable the Analog I2C Filter */
HAL_I2CEx_ConfigAnalogFilter(&i2cHandle[device].Handle,I2C_ANALOGFILTER_ENABLE);
HAL_I2C_Init(pHandle);
HAL_NVIC_SetPriority(i2cHardwareMap[device].er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER));
HAL_NVIC_EnableIRQ(i2cHardwareMap[device].er_irq);
HAL_NVIC_SetPriority(i2cHardwareMap[device].ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV));
HAL_NVIC_EnableIRQ(i2cHardwareMap[device].ev_irq);
// Enable the Analog I2C Filter
HAL_I2CEx_ConfigAnalogFilter(pHandle, I2C_ANALOGFILTER_ENABLE);
// Setup interrupt handlers
HAL_NVIC_SetPriority(hardware->er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER));
HAL_NVIC_EnableIRQ(hardware->er_irq);
HAL_NVIC_SetPriority(hardware->ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV));
HAL_NVIC_EnableIRQ(hardware->ev_irq);
}
uint16_t i2cGetErrorCounter(void)

View File

@ -0,0 +1,76 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* 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
#include "platform.h"
#include "drivers/io_types.h"
#include "drivers/rcc_types.h"
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
#define I2C_PIN_SEL_MAX 3
typedef struct i2cHardware_s {
I2CDevice device;
I2C_TypeDef *reg;
ioTag_t sclPins[I2C_PIN_SEL_MAX];
ioTag_t sdaPins[I2C_PIN_SEL_MAX];
rccPeriphTag_t rcc;
#if !defined(STM32F303xC)
uint8_t ev_irq;
uint8_t er_irq;
#endif
} i2cHardware_t;
extern const i2cHardware_t i2cHardware[];
#if defined(STM32F1) || defined(STM32F4)
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;
#endif
typedef struct i2cDevice_s {
const i2cHardware_t *hardware;
I2C_TypeDef *reg;
IO_t scl;
IO_t sda;
bool overClock;
bool pullUp;
// MCU/Driver dependent member follows
#if defined(STM32F1) || defined(STM32F4)
i2cState_t state;
#endif
#ifdef USE_HAL_DRIVER
I2C_HandleTypeDef handle;
#endif
} i2cDevice_t;
extern i2cDevice_t i2cDevice[];

View File

@ -18,18 +18,19 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/time.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h"
#include "drivers/bus_i2c.h"
#include "drivers/nvic.h"
#include "io_impl.h"
#include "rcc.h"
#include "drivers/bus_i2c_impl.h"
#ifndef SOFT_I2C
#if defined(USE_I2C) && !defined(SOFT_I2C)
#define CLOCKSPEED 800000 // i2c clockspeed 400kHz default (conform specs), 800kHz and 1200kHz (Betaflight default)
@ -40,65 +41,52 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#define GPIO_AF_I2C GPIO_AF_I2C1
#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
#define IOCFG_I2C_PU IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#else // STM32F4
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PB10
const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#ifdef USE_I2C_DEVICE_1
{
.device = I2CDEV_1,
.reg = I2C1,
.sclPins = { DEFIO_TAG_E(PB6), DEFIO_TAG_E(PB8) },
.sdaPins = { DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB9) },
.rcc = RCC_APB1(I2C1),
.ev_irq = I2C1_EV_IRQn,
.er_irq = I2C1_ER_IRQn,
},
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#ifdef USE_I2C_DEVICE_2
{
.device = I2CDEV_2,
.reg = I2C2,
.sclPins = { DEFIO_TAG_E(PB10), DEFIO_TAG_E(PF1) },
.sdaPins = { DEFIO_TAG_E(PB11), DEFIO_TAG_E(PF0) },
.rcc = RCC_APB1(I2C2),
.ev_irq = I2C2_EV_IRQn,
.er_irq = I2C2_ER_IRQn,
},
#endif
#ifdef STM32F4
#ifndef I2C3_SCL
#define I2C3_SCL PA8
#endif
#ifndef I2C3_SDA
#define I2C3_SDA PC9
#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 }
#ifdef USE_I2C_DEVICE_3
{
.device = I2CDEV_3,
.reg = I2C3,
.sclPins = { DEFIO_TAG_E(PA8) },
.sdaPins = { DEFIO_TAG_E(PC9) },
.rcc = RCC_APB1(I2C3),
.ev_irq = I2C3_EV_IRQn,
.er_irq = I2C3_ER_IRQn,
},
#endif
};
i2cDevice_t i2cDevice[I2CDEV_COUNT];
static volatile uint16_t i2cErrorCount = 0;
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 }
};
void I2C1_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_1);
}
@ -135,18 +123,19 @@ static bool i2cHandleHardwareFailure(I2CDevice device)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{
if (device == I2CINVALID)
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return false;
}
I2C_TypeDef *I2Cx = i2cDevice[device].reg;
if (!I2Cx) {
return false;
}
i2cState_t *state = &i2cDevice[device].state;
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;
@ -182,17 +171,19 @@ 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)
{
if (device == I2CINVALID)
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return false;
}
I2C_TypeDef *I2Cx = i2cDevice[device].reg;
if (!I2Cx) {
return false;
}
i2cState_t *state = &i2cDevice[device].state;
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;
@ -223,11 +214,9 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
static void i2c_er_handler(I2CDevice device) {
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2C_TypeDef *I2Cx = i2cDevice[device].hardware->reg;
i2cState_t *state;
state = &(i2cState[device]);
i2cState_t *state = &i2cDevice[device].state;
// Read the I2C1 status register
volatile uint32_t SR1Register = I2Cx->SR1;
@ -258,11 +247,9 @@ static void i2c_er_handler(I2CDevice device) {
void i2c_ev_handler(I2CDevice device) {
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2C_TypeDef *I2Cx = i2cDevice[device].hardware->reg;
i2cState_t *state;
state = &(i2cState[device]);
i2cState_t *state = &i2cDevice[device].state;
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
@ -378,65 +365,72 @@ void i2cInit(I2CDevice device)
if (device == I2CINVALID)
return;
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
i2cDevice_t *pDev = &i2cDevice[device];
const i2cHardware_t *hw = pDev->hardware;
if (!hw) {
return;
}
I2C_TypeDef *I2Cx = hw->reg;
memset(&pDev->state, 0, sizeof(pDev->state));
NVIC_InitTypeDef nvic;
I2C_InitTypeDef i2cInit;
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
IO_t scl = pDev->scl;
IO_t sda = pDev->sda;
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
// Enable RCC
RCC_ClockCmd(i2c->rcc, ENABLE);
RCC_ClockCmd(hw->rcc, ENABLE);
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
i2cUnstick(scl, sda);
// Init pins
#ifdef STM32F4
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF_I2C);
#else
IOConfigGPIO(scl, IOCFG_I2C);
IOConfigGPIO(sda, IOCFG_I2C);
#endif
I2C_DeInit(i2c->dev);
I2C_DeInit(I2Cx);
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
I2C_ITConfig(I2Cx, 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) {
if (pDev->overClock) {
i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
} else {
i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs
}
I2C_Cmd(i2c->dev, ENABLE);
I2C_Init(i2c->dev, &i2cInit);
I2C_StretchClockCmd(i2c->dev, ENABLE);
I2C_Cmd(I2Cx, ENABLE);
I2C_Init(I2Cx, &i2cInit);
I2C_StretchClockCmd(I2Cx, ENABLE);
// I2C ER Interrupt
nvic.NVIC_IRQChannel = i2c->er_irq;
nvic.NVIC_IRQChannel = hw->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 = i2c->ev_irq;
nvic.NVIC_IRQChannel = hw->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);

View File

@ -17,54 +17,57 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <platform.h>
#include "build/debug.h"
#include "drivers/system.h"
#include "drivers/io.h"
#include "io_impl.h"
#include "rcc.h"
#include "drivers/io_impl.h"
#include "drivers/rcc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_impl.h"
#ifndef SOFT_I2C
#if defined(USE_I2C) && !defined(SOFT_I2C)
#if defined(USE_I2C_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP)
#else
#define IOCFG_I2C_PU IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP)
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#endif
#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 i2cErrorCount = 0;
//static volatile uint16_t i2c2ErrorCount = 0;
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 }
const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#ifdef USE_I2C_DEVICE_1
{
.device = I2CDEV_1,
.reg = I2C1,
.sclPins = { DEFIO_TAG_E(PA15), DEFIO_TAG_E(PB6), DEFIO_TAG_E(PB8) },
.sdaPins = { DEFIO_TAG_E(PA14), DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB9) },
.rcc = RCC_APB1(I2C1),
},
#endif
#ifdef USE_I2C_DEVICE_2
{
.device = I2CDEV_2,
.reg = I2C2,
.sclPins = { DEFIO_TAG_E(PA9), DEFIO_TAG_E(PF6) },
.sdaPins = { DEFIO_TAG_E(PA10) },
.rcc = RCC_APB1(I2C2),
},
#endif
};
i2cDevice_t i2cDevice[I2CDEV_COUNT];
///////////////////////////////////////////////////////////////////////////////
// I2C TimeoutUserCallback
///////////////////////////////////////////////////////////////////////////////
@ -77,24 +80,30 @@ uint32_t i2cTimeoutUserCallback(void)
void i2cInit(I2CDevice device)
{
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return;
}
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
i2cDevice_t *pDev = &i2cDevice[device];
const i2cHardware_t *hw = pDev->hardware;
I2C_TypeDef *I2Cx;
I2Cx = i2c->dev;
if (!hw) {
return;
}
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
I2C_TypeDef *I2Cx = pDev->reg;
RCC_ClockCmd(i2c->rcc, ENABLE);
IO_t scl = pDev->scl;
IO_t sda = pDev->sda;
RCC_ClockCmd(hw->rcc, ENABLE);
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF_4);
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF_4);
I2C_InitTypeDef i2cInit = {
.I2C_Mode = I2C_Mode_I2C,
@ -103,7 +112,7 @@ void i2cInit(I2CDevice device)
.I2C_OwnAddress1 = 0x00,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
.I2C_Timing = (pDev->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
};
I2C_Init(I2Cx, &i2cInit);
@ -120,10 +129,17 @@ uint16_t i2cGetErrorCounter(void)
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
{
addr_ <<= 1;
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return false;
}
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2C_TypeDef *I2Cx = i2cDevice[device].reg;
if (!I2Cx) {
return false;
}
addr_ <<= 1;
/* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT;
@ -186,10 +202,17 @@ 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)
{
addr_ <<= 1;
if (device == I2CINVALID || device > I2CDEV_COUNT) {
return false;
}
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
I2C_TypeDef *I2Cx = i2cDevice[device].reg;
if (!I2Cx) {
return false;
}
addr_ <<= 1;
/* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT;

View File

@ -24,6 +24,8 @@
#include "display_ug2864hsweg01.h"
#ifdef USE_I2C_OLED_DISPLAY
#if !defined(OLED_I2C_INSTANCE)
#if defined(I2C_DEVICE)
#define OLED_I2C_INSTANCE I2C_DEVICE
@ -288,3 +290,4 @@ bool ug2864hsweg01InitI2C(void)
return true;
}
#endif // USE_I2C_OLED_DISPLAY

View File

@ -2749,6 +2749,10 @@ const cliResourceValue_t resourceTable[] = {
#ifdef USE_INVERTER
{ OWNER_INVERTER, PG_SERIAL_PIN_CONFIG, offsetof(serialPinConfig_t, ioTagInverter[0]), SERIAL_PORT_MAX_INDEX },
#endif
#ifdef USE_I2C
{ OWNER_I2C_SCL, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagScl[0]), I2CDEV_COUNT },
{ OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT },
#endif
};
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)

View File

@ -27,6 +27,7 @@
#include "drivers/rx_pwm.h"
#include "drivers/sdcard.h"
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
#include "drivers/sound_beeper.h"
#include "drivers/vcd.h"

View File

@ -54,6 +54,7 @@
#include "drivers/rx_pwm.h"
#include "drivers/pwm_output.h"
#include "drivers/adc.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/buttons.h"
@ -135,10 +136,6 @@
void targetPreInit(void);
#endif
#ifdef TARGET_BUS_INIT
void targetBusInit(void);
#endif
extern uint8_t motorControlEnable;
#ifdef SOFTSERIAL_LOOPBACK
@ -367,6 +364,11 @@ void init(void)
#endif /* USE_SPI */
#ifdef USE_I2C
i2cHardwareConfigure();
// Note: Unlike UARTs which are configured when client is present,
// I2C buses are initialized unconditionally if they are configured.
#ifdef USE_I2C_DEVICE_1
i2cInit(I2CDEV_1);
#endif

View File

@ -34,6 +34,7 @@
#include "config/parameter_group_ids.h"
#include "drivers/adc.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/dma.h"
@ -92,10 +93,6 @@
void targetPreInit(void);
#endif
#ifdef TARGET_BUS_INIT
void targetBusInit(void);
#endif
uint8_t systemState = SYSTEM_STATE_INITIALISING;
void processLoopback(void)
@ -195,6 +192,11 @@ void init(void)
#endif /* USE_SPI */
#ifdef USE_I2C
i2cHardwareConfigure();
// Note: Unlike UARTs which are configured when client is present,
// I2C buses are initialized unconditionally if they are configured.
#ifdef USE_I2C_DEVICE_1
i2cInit(I2CDEV_1);
#endif

View File

@ -19,7 +19,6 @@
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define TARGET_CONFIG
#define TARGET_BUS_INIT
#define REMAP_TIM17_DMA
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT

View File

@ -127,6 +127,7 @@
//#define SPI_RX_CS_PIN PD2
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB6
#define I2C1_SDA PB7

View File

@ -19,6 +19,7 @@
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "io/serial.h"
@ -31,6 +32,7 @@ void targetBusInit(void)
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
serialRemovePort(SERIAL_PORT_USART3);
i2cHardwareConfigure();
i2cInit(I2C_DEVICE);
}
}

View File

@ -87,7 +87,8 @@
#define SERIAL_PORT_COUNT 5
#define USE_I2C
// XXX To target maintainer: Bus device to configure must be specified.
//#define USE_I2C
#define USE_SPI
#define USE_SPI_DEVICE_1

View File

@ -16,9 +16,11 @@
*/
#include <stdint.h>
#include <stdbool.h>
#include <platform.h>
#include "drivers/bus_i2c.h"
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
@ -46,10 +48,12 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
};
// XXX Requires some additional work here.
// XXX Can't do this now without proper semantics about I2C on this target.
#ifdef USE_BST
void targetBusInit(void)
{
i2cHardwareConfigure();
bstInit(BST_DEVICE);
}
#endif

View File

@ -0,0 +1,30 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#ifdef TARGET_CONFIG
#include "rx/rx.h"
#include "io/serial.h"
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
rxConfigMutable()->rssi_channel = 8;
}
#endif

View File

@ -0,0 +1,37 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/timer.h"
#include "drivers/dma.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM1
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM2
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM3
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM4
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM5
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM6
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM7
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD), // PWM8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED|TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), // LED
};

View File

@ -0,0 +1,151 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* 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 "FRF3"
#define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3
#define BEEPER PC15
#define BEEPER_INVERTED
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT, SDCardDetect
#define MPU_ADDRESS 0x69
#ifdef MYMPU6000
#define MPU6000_SPI_INSTANCE SPI2
#define MPU6000_CS_PIN PB12
#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
#else
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#endif
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 6
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0
#define USE_SPI
#define OSD
// include the max7456 driver
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PB4
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SPI
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_1
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define SPI1_NSS_PIN PC14
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SDCARD
#define USE_SDCARD_SPI1
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB5
#define SDCARD_SPI_INSTANCE SPI1
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4
#define USE_ESC_SENSOR
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_NONE
#define USE_ADC
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PB2
#define ADC_INSTANCE ADC2
#define ADC24_DMA_REMAP
#define TRANSPONDER
#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define DEFAULT_FEATURES ( FEATURE_TELEMETRY | FEATURE_LED_STRIP | FEATURE_OSD)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define TELEMETRY_UART SERIAL_PORT_USART3
#define SERIALRX_UART SERIAL_PORT_USART2
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#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(4))
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(17))

View File

@ -0,0 +1,13 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/max7456.c

View File

@ -0,0 +1,30 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#ifdef TARGET_CONFIG
#include "rx/rx.h"
#include "io/serial.h"
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
rxConfigMutable()->rssi_channel = 8;
}
#endif

View File

@ -0,0 +1,43 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PWM | TIM_USE_PPM, TIMER_OUTPUT_NONE, 0), // PPM
DEF_TIM(TIM4, CH4, PB9, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S3_IN, UART6_TX
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S4_IN, UART6_RX
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S5_IN
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, TIMER_OUTPUT_NONE, 0), // S6_IN
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S1_OUT D1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S2_OUT D1_ST2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 1), // S3_OUT D1_ST6
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S4_OUT D1_ST1
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S6_OUT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
};

View File

@ -0,0 +1,140 @@
/*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This software is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "FRF4"
#define USBD_PRODUCT_STRING "FRSKYF4"
#define TARGET_CONFIG
#define LED0 PB5
#define BEEPER PB4
#define BEEPER_INVERTED
#define INVERTER_PIN_UART6 PC8
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define ACC_MPU6000_ALIGN CW270_DEG
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
//#define MAG
//#define USE_MAG_HMC5883
//#define MAG_HMC5883_ALIGN CW90_DEG
#define BARO
//#define USE_BARO_MS5611
#define USE_BARO_BMP280
#define USE_BARO_SPI_BMP280
#define BMP280_SPI_INSTANCE SPI3
#define BMP280_CS_PIN PB3
#define OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
#define MAX7456_SPI_CS_PIN PA15
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 6
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_ADC
#define CURRENT_METER_ADC_PIN PC1
#define VBAT_ADC_PIN PC2
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_OSD)
#define AVOID_UART1_FOR_PWM_PPM
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define TELEMETRY_UART SERIAL_PORT_USART6
#define SERIALRX_UART SERIAL_PORT_USART1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
#define TARGET_IO_PORTB (0xffff & ~(BIT(2)))
#define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13)))
#define TARGET_IO_PORTD BIT(2)
#define USABLE_TIMER_CHANNEL_COUNT 13
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))

View File

@ -0,0 +1,11 @@
F405_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/max7456.c

View File

@ -127,6 +127,7 @@
#endif
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL PB8
#define I2C1_SDA PB9

View File

@ -21,33 +21,6 @@
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
void targetBusInit(void)
{
#ifdef USE_SPI
#ifdef USE_SPI_DEVICE_1
spiInit(SPIDEV_1);
#endif
#ifdef USE_SPI_DEVICE_2
spiInit(SPIDEV_2);
#endif
#ifdef USE_SPI_DEVICE_3
spiInit(SPIDEV_3);
#endif
#ifdef USE_SPI_DEVICE_4
spiInit(SPIDEV_4);
#endif
#endif
#ifdef USE_I2C
#ifdef USE_I2C_DEVICE_1
i2cInit(I2CDEV_1);
#endif
#ifdef USE_I2C_DEVICE_3
i2cInit(I2CDEV_3);
#endif
#endif
}
void targetPreInit(void)
{
IO_t osdChSwitch = IOGetByTag(IO_TAG(OSD_CH_SWITCH));

View File

@ -25,7 +25,6 @@
#define USBD_PRODUCT_STRING "KroozX"
#define TARGET_CONFIG
#define TARGET_BUS_INIT
#define TARGET_PREINIT
#define LED0 PA14 // Red LED

View File

@ -88,8 +88,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 8
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) )
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL PB2
#define I2C2_SDA PB1

View File

@ -19,6 +19,7 @@
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "io/serial.h"
@ -37,9 +38,11 @@ void targetBusInit(void)
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
serialRemovePort(SERIAL_PORT_USART3);
i2cHardwareConfigure();
i2cInit(I2C_DEVICE);
}
} else {
i2cHardwareConfigure();
i2cInit(I2C_DEVICE);
}
}

View File

@ -78,13 +78,14 @@
#define UART2_TX_PIN PA14 // PA14 / SWCLK
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10 // PB10 (PWM5)
#define UART3_RX_PIN PB11 // PB11 (PWM6)
#undef USE_I2C
//#define USE_I2C
//#define USE_I2C_DEVICE_1
//#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL NONE // PB6 (PWM8)
#define I2C1_SDA NONE // PB7 (PWM7)
#define I2C_DEVICE (I2CDEV_1)
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1

View File

@ -185,6 +185,18 @@
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL NONE // PB10, shared with UART3TX
#define I2C2_SDA NONE // PB11, shared with UART3RX
#if defined(OMNIBUSF4) || defined(OMNIBUSF4SD)
#define USE_I2C_DEVICE_3
#define I2C3_SCL NONE // PA8, PWM6
#define I2C3_SDA NONE // PC9, CH6
#endif
#define I2C_DEVICE (I2CDEV_2)
#define OLED_I2C_INSTANCE (I2CDEV_3)
#define USE_ADC
#define CURRENT_METER_ADC_PIN PC1
#define VBAT_ADC_PIN PC2

View File

@ -135,6 +135,8 @@
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL NONE // PB10 (UART3_TX)
#define I2C2_SDA NONE // PB11 (UART3_RX)
#define BARO
#define USE_BARO_BMP280

View File

@ -136,7 +136,7 @@
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#if !defined(AIRBOTF4) && !defined(REVOLT) && !defined(SOULF4) && !defined(PODIUMF4)
#if defined(AIRBOTF4) || defined(AIRBOTF4SD)
#define MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
@ -224,9 +224,17 @@
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#if defined(AIRBOTF4) || defined(AIRBOTF4SD)
// On AIRBOTF4 and AIRBOTF4SD, I2C2 and I2C3 are configurable
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_2
#define I2C2_SCL NONE // PB10, shared with UART3TX
#define I2C2_SDA NONE // PB11, shared with UART3RX
#define USE_I2C_DEVICE_3
#define I2C3_SCL NONE // PA8, PWM6
#define I2C3_SDA NONE // PC9, CH6
#define I2C_DEVICE (I2CDEV_2)
#endif
#define USE_ADC
#if !defined(PODIUMF4)

View File

@ -89,6 +89,7 @@
// #define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#if (SPRACINGF4EVO_REV >= 2)
#define I2C1_SCL PB8

View File

@ -102,6 +102,7 @@
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#if (SPRACINGF4NEO_REV >= 3)

View File

@ -28,3 +28,14 @@
#if defined(USE_QUAD_MIXER_ONLY) && defined(USE_SERVOS)
#undef USE_SERVOS
#endif
// XXX Followup implicit dependencies among DASHBOARD, display_xxx and USE_I2C.
// XXX This should eventually be cleaned up.
#ifndef USE_I2C
#undef USE_I2C_OLED_DISPLAY
#undef USE_DASHBOARD
#else
#ifdef USE_DASHBOARD
#define USE_I2C_OLED_DISPLAY
#endif
#endif