1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 17:55:28 +03:00

Merge pull request #2548 from iNavFlight/de_busdev_i2c

Conversion to busDevice (further steps & cleanups)
This commit is contained in:
Konstantin Sharlaimov 2017-12-06 23:43:40 +10:00 committed by GitHub
commit 215bedc3be
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
61 changed files with 229 additions and 199 deletions

View file

@ -23,10 +23,6 @@
#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro_mpu.h"
#ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE
#endif
#define GYRO_LPF_256HZ 0
#define GYRO_LPF_188HZ 1
#define GYRO_LPF_98HZ 2

View file

@ -28,10 +28,6 @@
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_mma845x.h"
#ifndef MMA8452_I2C_INSTANCE
#define MMA8452_I2C_INSTANCE I2CDEV_1
#endif
// MMA8452QT, Standard address 0x1C
// ACC_INT2 routed to PA5

View file

@ -104,6 +104,10 @@ typedef enum {
DEVHW_SRF10,
DEVHW_HCSR04_I2C, // DIY-style adapter
DEVHW_VL53L0X,
/* Other hardware */
DEVHW_MS4525, // Pitot meter
DEVHW_PCA9685, // PWM output device
} devHardwareType_e;
typedef enum {

View file

@ -27,10 +27,6 @@
#include "drivers/io_types.h"
#include "drivers/rcc_types.h"
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID
#endif
typedef enum { // Weird mapping to keep config compatible with previos version
I2C_SPEED_100KHZ = 2,
I2C_SPEED_200KHZ = 3,
@ -40,6 +36,7 @@ typedef enum { // Weird mapping to keep config compatible with previos version
typedef enum I2CDevice {
I2CINVALID = -1,
I2CDEV_EMULATED = -1, // Hack until we have proper I2C abstraction
I2CDEV_1 = 0,
I2CDEV_2,
I2CDEV_3,

View file

@ -86,8 +86,8 @@ static bool qmc5883Init(magDev_t * mag)
bool ack = true;
ack = ack && busWrite(mag->busDev, 0x0B, 0x01);
// ack = ack && i2cWrite(MAG_I2C_INSTANCE, QMC5883L_MAG_I2C_ADDRESS, 0x20, 0x40);
// ack = ack && i2cWrite(MAG_I2C_INSTANCE, QMC5883L_MAG_I2C_ADDRESS, 0x21, 0x01);
// ack = ack && i2cWrite(busWrite(mag->busDev, 0x20, 0x40);
// ack = ack && i2cWrite(busWrite(mag->busDev, 0x21, 0x01);
ack = ack && busWrite(mag->busDev, QMC5883L_REG_CONF1, QMC5883L_MODE_CONTINUOUS | QMC5883L_ODR_200HZ | QMC5883L_OSR_512 | QMC5883L_RNG_8G);
return ack;

View file

@ -1,14 +1,18 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "platform.h"
#include "drivers/gpio.h"
#include "drivers/time.h"
#include "drivers/bus_i2c.h"
#include "build/build_config.h"
#include "common/time.h"
#include "common/maths.h"
#include "drivers/io.h"
#include "drivers/time.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#define PCA9685_ADDR 0x40
#define PCA9685_MODE1 0x00
#define PCA9685_PRESCALE 0xFE
@ -22,20 +26,21 @@
#define PCA9685_SERVO_COUNT 16
#define PCA9685_SYNC_THRESHOLD 5
uint16_t currentOutputState[PCA9685_SERVO_COUNT] = {0};
uint16_t temporaryOutputState[PCA9685_SERVO_COUNT] = {0};
static busDevice_t * busDev;
static uint16_t currentOutputState[PCA9685_SERVO_COUNT] = {0};
static uint16_t temporaryOutputState[PCA9685_SERVO_COUNT] = {0};
void pca9685setPWMOn(uint8_t servoIndex, uint16_t on) {
if (servoIndex < PCA9685_SERVO_COUNT) {
i2cWrite(I2C_DEVICE, PCA9685_ADDR, LED0_ON_L + (servoIndex * 4), on);
i2cWrite(I2C_DEVICE, PCA9685_ADDR, LED0_ON_H + (servoIndex * 4), on>>8);
busWrite(busDev, LED0_ON_L + (servoIndex * 4), on);
busWrite(busDev, LED0_ON_H + (servoIndex * 4), on>>8);
}
}
void pca9685setPWMOff(uint8_t servoIndex, uint16_t off) {
if (servoIndex < PCA9685_SERVO_COUNT) {
i2cWrite(I2C_DEVICE, PCA9685_ADDR, LED0_OFF_L + (servoIndex * 4), off);
i2cWrite(I2C_DEVICE, PCA9685_ADDR, LED0_OFF_H + (servoIndex * 4), off>>8);
busWrite(busDev, LED0_OFF_L + (servoIndex * 4), off);
busWrite(busDev, LED0_OFF_H + (servoIndex * 4), off>>8);
}
}
@ -87,31 +92,45 @@ void pca9685setPWMFreq(uint16_t freq) {
prescaleval /= freq;
prescaleval -= 1;
i2cWrite(I2C_DEVICE, PCA9685_ADDR, PCA9685_MODE1, 16);
busWrite(busDev, PCA9685_MODE1, 16);
delay(1);
i2cWrite(I2C_DEVICE, PCA9685_ADDR, PCA9685_PRESCALE, (uint8_t) prescaleval);
busWrite(busDev, PCA9685_PRESCALE, (uint8_t) prescaleval);
delay(1);
i2cWrite(I2C_DEVICE, PCA9685_ADDR, PCA9685_MODE1, 128);
busWrite(busDev, PCA9685_MODE1, 128);
}
bool pca9685Initialize(void) {
bool ack = false;
static bool deviceDetect(busDevice_t * busDev)
{
for (int retry = 0; retry < 5; retry++) {
uint8_t sig;
ack = i2cRead(I2C_DEVICE, PCA9685_ADDR, PCA9685_MODE1, 1, &sig);
delay(150);
bool ack = busRead(busDev, PCA9685_MODE1, &sig);
if (ack) {
return true;
}
};
if (!ack) {
return false;
} else {
/*
Reset device
*/
i2cWrite(I2C_DEVICE, PCA9685_ADDR, PCA9685_MODE1, 0x0);
}
/*
Set refresh rate
*/
bool pca9685Initialize(void)
{
busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_PCA9685, 0, 0);
if (busDev == NULL) {
return false;
}
if (!deviceDetect(busDev)) {
busDeviceDeInit(busDev);
return false;
}
/* Reset device */
busWrite(busDev, PCA9685_MODE1, 0x00);
/* Set refresh rate */
pca9685setPWMFreq(PCA9685_SERVO_FREQUENCY);
delay(1);
@ -122,5 +141,4 @@ bool pca9685Initialize(void) {
}
return true;
}
}

View file

@ -16,17 +16,17 @@
*/
#pragma once
#include "drivers/bus.h"
typedef void (*pitotOpFuncPtr)(void); // pitot start operation
typedef void (*pitotCalculateFuncPtr)(float *pressure, float *temperature); // airspeed calculation (filled params are pressure and temperature)
struct pitotDev_s;
typedef struct pitotDev_t {
typedef void (*pitotOpFuncPtr)(struct pitotDev_s * pitot); // pitot start operation
typedef void (*pitotCalculateFuncPtr)(struct pitotDev_s * pitot, float *pressure, float *temperature); // airspeed calculation (filled params are pressure and temperature)
typedef struct pitotDev_s {
busDevice_t * busDev;
uint16_t delay;
pitotOpFuncPtr start;
pitotOpFuncPtr get;
pitotCalculateFuncPtr calculate;
} pitotDev_t;
#ifndef PITOT_I2C_INSTANCE
#define PITOT_I2C_INSTANCE I2C_DEVICE
#endif

View file

@ -22,6 +22,8 @@
#include "build/build_config.h"
#include "common/utils.h"
#include "pitotmeter.h"
#include "pitotmeter_adc.h"
#include "adc.h"
@ -36,16 +38,19 @@
#define PITOT_ADC_VOLTAGE_ZERO (2.5f) // Pressure offset is 2.5V
#define PITOT_ADC_VOLTAGE_TO_PRESSURE (1000.0f) // 1V/kPa = 1000 Pa/V
static void adcPitotStart(void)
static void adcPitotStart(pitotDev_t *pitot)
{
UNUSED(pitot);
}
static void adcPitotRead(void)
static void adcPitotRead(pitotDev_t *pitot)
{
UNUSED(pitot);
}
static void adcPitotCalculate(float *pressure, float *temperature)
static void adcPitotCalculate(pitotDev_t *pitot, float *pressure, float *temperature)
{
UNUSED(pitot);
uint16_t adcRaw = adcGetChannel(ADC_AIRSPEED);
float voltage = (float)adcRaw * (3.3f / 4095.0f); // 12 bit ADC with 3.3V VREF

View file

@ -22,6 +22,8 @@
#include "build/build_config.h"
#include "common/utils.h"
#include "pitotmeter.h"
#include "pitotmeter_fake.h"
@ -29,16 +31,19 @@
static int32_t fakePressure;
static int32_t fakeTemperature;
static void fakePitotStart(void)
static void fakePitotStart(pitotDev_t *pitot)
{
UNUSED(pitot);
}
static void fakePitotRead(void)
static void fakePitotRead(pitotDev_t *pitot)
{
UNUSED(pitot);
}
static void fakePitotCalculate(float *pressure, float *temperature)
static void fakePitotCalculate(pitotDev_t *pitot, float *pressure, float *temperature)
{
UNUSED(pitot);
if (pressure)
*pressure = fakePressure; // Pa
if (temperature)

View file

@ -28,60 +28,28 @@
// MS4525, Standard address 0x28
#define MS4525_ADDR 0x28
//#define MS4525_ADDR 0x36
//#define MS4525_ADDR 0x46
static void ms4525_start(void);
static void ms4525_read(void);
static void ms4525_calculate(float *pressure, float *temperature);
static uint16_t ms4525_ut; // static result of temperature measurement
static uint16_t ms4525_up; // static result of pressure measurement
static uint8_t rxbuf[4];
bool ms4525Detect(pitotDev_t *pitot)
static void ms4525_start(pitotDev_t * pitot)
{
bool ack = false;
// Read twice to fix:
// Sending a start-stop condition without any transitions on the SCL line (no clock pulses in between) creates a
// communication error for the next communication, even if the next start condition is correct and the clock pulse is applied.
// An additional start condition must be sent, which results in restoration of proper communication.
ack = i2cRead( PITOT_I2C_INSTANCE, MS4525_ADDR, 0xFF, 4, rxbuf );
ack = i2cRead( PITOT_I2C_INSTANCE, MS4525_ADDR, 0xFF, 4, rxbuf );
if (!ack)
return false;
pitot->delay = 10000;
pitot->start = ms4525_start;
pitot->get = ms4525_read;
pitot->calculate = ms4525_calculate;
ms4525_read();
return true;
busReadBuf( pitot->busDev, 0xFF, rxbuf, 4 );
}
static void ms4525_start(void)
static void ms4525_read(pitotDev_t * pitot)
{
i2cRead( PITOT_I2C_INSTANCE, MS4525_ADDR, 0xFF, 4, rxbuf );
}
static void ms4525_read(void)
{
if (i2cRead( PITOT_I2C_INSTANCE, MS4525_ADDR, 0xFF, 4, rxbuf )) {
if (busReadBuf( pitot->busDev, 0xFF, rxbuf, 4 )) {
ms4525_up = (rxbuf[0] << 8) | (rxbuf[1] << 0);
ms4525_ut = ((rxbuf[2] << 8) | (rxbuf[3] << 0))>>5;
}
}
void voltage_correction(float *pressure, float *temperature)
static void ms4525_calculate(pitotDev_t * pitot, float *pressure, float *temperature)
{
UNUSED(pressure);
UNUSED(temperature);
}
UNUSED(pitot);
static void ms4525_calculate(float *pressure, float *temperature)
{
uint8_t status = (ms4525_up & 0xC000) >> 14;
switch (status) {
case 0:
@ -108,3 +76,29 @@ static void ms4525_calculate(float *pressure, float *temperature)
*temperature = T; // K
}
bool ms4525Detect(pitotDev_t * pitot)
{
pitot->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_MS4525, 0, OWNER_AIRSPEED);
if (pitot->busDev == NULL) {
return false;
}
bool ack = false;
// Read twice to fix:
// Sending a start-stop condition without any transitions on the SCL line (no clock pulses in between) creates a
// communication error for the next communication, even if the next start condition is correct and the clock pulse is applied.
// An additional start condition must be sent, which results in restoration of proper communication.
ack = busReadBuf( pitot->busDev, 0xFF, rxbuf, 4 );
ack = busReadBuf( pitot->busDev, 0xFF, rxbuf, 4 );
if (!ack) {
return false;
}
pitot->delay = 10000;
pitot->start = ms4525_start;
pitot->get = ms4525_read;
pitot->calculate = ms4525_calculate;
ms4525_read(pitot);
return true;
}

View file

@ -55,7 +55,6 @@ void hcsr04i2cUpdate(rangefinderDev_t *rangefinder)
uint8_t response[3];
isHcsr04i2cResponding = busReadBuf(rangefinder->busDev, HCSR04_I2C_REGISTRY_STATUS, response, 3);
isHcsr04i2cResponding = i2cRead(I2C_DEVICE, HCSR04_I2C_Address, HCSR04_I2C_REGISTRY_STATUS, 3, response);
if (!isHcsr04i2cResponding) {
hcsr04i2cMeasurementCm = RANGEFINDER_HARDWARE_FAILURE;

View file

@ -31,10 +31,6 @@
#include "drivers/rangefinder/rangefinder.h"
#include "drivers/rangefinder/rangefinder_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
// see http://www.robot-electronics.co.uk/htm/sonar_faq.htm for cone angles

View file

@ -51,6 +51,7 @@ typedef enum {
OWNER_VTX,
OWNER_SPI_PREINIT,
OWNER_COMPASS,
OWNER_AIRSPEED,
OWNER_TOTAL_COUNT
} resourceOwner_e;

View file

@ -422,23 +422,41 @@ void init(void)
#endif
#ifdef USE_I2C
#if defined(I2C_DEVICE)
#if defined(I2C_DEVICE_SHARES_UART3)
#ifdef USE_I2C_DEVICE_1
#ifdef I2C_DEVICE_1_SHARES_UART3
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
i2cInit(I2C_DEVICE);
i2cInit(I2CDEV_1);
}
#else
i2cInit(I2C_DEVICE);
i2cInit(I2CDEV_1);
#endif
#endif
#if defined(I2C_DEVICE_EXT)
#if defined(I2C_DEVICE_EXT_SHARES_UART3)
#ifdef USE_I2C_DEVICE_2
#ifdef I2C_DEVICE_2_SHARES_UART3
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
i2cInit(I2C_DEVICE_EXT);
i2cInit(I2CDEV_2);
}
#else
i2cInit(I2C_DEVICE_EXT);
i2cInit(I2CDEV_2);
#endif
#endif
#ifdef USE_I2C_DEVICE_3
i2cInit(I2CDEV_3);
#endif
#ifdef USE_I2C_DEVICE_4
i2cInit(I2CDEV_4);
#endif
#ifdef USE_I2C_DEVICE_EMULATED
#ifdef I2C_DEVICE_EMULATED_SHARES_UART3
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
i2cInit(I2CDEV_EMULATED);
}
#else
i2cInit(I2CDEV_EMULATED);
#endif
#endif
#endif

View file

@ -200,14 +200,14 @@ uint32_t pitotUpdate(void)
switch (state) {
default:
case PITOTMETER_NEEDS_SAMPLES:
pitot.dev.start();
pitot.dev.start(&pitot.dev);
state = PITOTMETER_NEEDS_CALCULATION;
return pitot.dev.delay;
break;
case PITOTMETER_NEEDS_CALCULATION:
pitot.dev.get();
pitot.dev.calculate(&pitotPressure, &pitotTemperature);
pitot.dev.get(&pitot.dev);
pitot.dev.calculate(&pitot.dev, &pitotPressure, &pitotTemperature);
DEBUG_SET(DEBUG_PITOT, 0, pitotPressure);
if (pitotmeterConfig()->use_median_filtering) {
pitotPressure = applyPitotmeterMedianFilter(pitotPressure);

View file

@ -28,8 +28,8 @@
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C_DEVICE_SHARES_UART3
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
// MPU6000 interrupts
#define USE_EXTI
@ -70,7 +70,7 @@
#define USE_PITOT_ADC
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE
#define PITOT_I2C_BUS BUS_I2C2
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3

View file

@ -51,7 +51,6 @@
#define USE_BARO
#define USE_BARO_BMP280
#define USE_PITOT_MS4525
#define USE_PITOT_ADC
#define USE_UART1
@ -101,7 +100,7 @@
#ifdef AIRHEROF3_QUAD
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
#define USE_I2C_DEVICE_1 // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL PB8
#define I2C1_SDA PB9

View file

@ -91,8 +91,7 @@
#define USE_I2C
#define USE_I2C_PULLUP
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define USE_I2C_DEVICE_2 // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL PA9
#define I2C2_SDA PA10

View file

@ -143,8 +143,8 @@
#define SPI3_MOSI_PIN PB5
#define USE_I2C
#define USE_I2C_DEVICE_1
#define USE_I2C_PULLUP
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB6
#define I2C1_SDA PB7

View file

@ -152,7 +152,7 @@
#define USE_I2C
#define USE_I2C_PULLUP
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7

View file

@ -62,7 +62,7 @@
#define USE_BARO_MS5611
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE_EXT
#define PITOT_I2C_BUS BUS_I2C2
#define USB_IO
#define USE_VCP
@ -98,9 +98,9 @@
#define USE_SPI_DEVICE_1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define I2C_DEVICE_EXT (I2CDEV_2)
#define I2C_DEVICE_EXT_SHARES_UART3
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
//#define USE_I2C_PULLUP
//#define HIL

View file

@ -62,7 +62,7 @@
#endif
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE_EXT
#define PITOT_I2C_BUS BUS_I2C2
#define USABLE_TIMER_CHANNEL_COUNT 16
@ -150,8 +150,7 @@
#define USE_I2C
#define USE_I2C_DEVICE_4
#define I2C_DEVICE (I2CDEV_4)
#define I2C_DEVICE_EXT (I2CDEV_2)
#define USE_I2C_DEVICE_2
//#define USE_I2C_PULLUP
//#define HIL

View file

@ -54,7 +54,7 @@
#define USE_BARO_MS5611
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE
#define PITOT_I2C_BUS BUS_I2C2
#define USABLE_TIMER_CHANNEL_COUNT 16
@ -121,7 +121,6 @@
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C_DEVICE (I2CDEV_2)
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC0

View file

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

View file

@ -64,8 +64,6 @@
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
@ -130,7 +128,7 @@
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define USE_I2C_PULLUP
#define USE_ADC

View file

@ -33,8 +33,8 @@
#define USE_SPI_DEVICE_2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
#define I2C_DEVICE_SHARES_UART3
#define USE_I2C_DEVICE_2 // Flex port - SCL/PB10, SDA/PB11
#define I2C_DEVICE_2_SHARES_UART3
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1

View file

@ -63,7 +63,7 @@
#define SERIAL_PORT_COUNT 3
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define USE_ADC
#define ADC_INSTANCE ADC1

View file

@ -119,7 +119,7 @@
#define SPI2_MOSI_PIN PC3
#define USE_I2C
#define I2C_DEVICE (I2CDEV_3)
#define USE_I2C_DEVICE_3
#define I2C3_SCL PA8
#define I2C3_SDA PC9

View file

@ -93,7 +93,7 @@
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10

View file

@ -45,7 +45,7 @@
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_1

View file

@ -84,7 +84,7 @@
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
// #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)

View file

@ -120,7 +120,7 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11

View file

@ -54,7 +54,6 @@
#define USE_MAG_HMC5883
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define MAG_I2C_INSTANCE I2C_DEVICE_EXT
#define USB_IO
@ -91,12 +90,12 @@
#define SPI2_MOSI_PIN PB15
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define I2C_DEVICE_EXT (I2CDEV_2)
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10

View file

@ -116,7 +116,7 @@
#define SPI3_MOSI_PIN PB5
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11

View file

@ -145,7 +145,7 @@
// *************** IIC *****************************
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9

View file

@ -59,7 +59,6 @@
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB6
#define I2C1_SDA PB7

View file

@ -131,7 +131,7 @@
#define SOFTSERIAL_1_TX_PIN PB1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
#define USE_I2C_DEVICE_1 // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL PB8
#define I2C1_SDA PB9

View file

@ -104,13 +104,13 @@
#define UART2_RX_PIN PA3
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define I2C1_SCL PA15
#define I2C1_SDA PA14
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE
#define PITOT_I2C_BUS BUS_I2C1
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC

View file

@ -114,10 +114,12 @@
#define SERIAL_PORT_COUNT 6
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define I2C_DEVICE_EXT (I2CDEV_3)
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_I2C_DEVICE_3
#define I2C3_SCL PA8
#define I2C3_SDA PC9

View file

@ -78,7 +78,7 @@
#define UART3_RX_PIN PB11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
#define USE_ADC
#define ADC_INSTANCE ADC1

View file

@ -118,17 +118,21 @@
#ifdef MATEKF405OSD
// OSD - no native I2C
#define USE_I2C
#define USE_I2C_DEVICE_EMULATED
#define I2C_DEVICE_EMULATED_SHARES_UART3
#define SOFT_I2C
#define DEFAULT_I2C_BUS BUS_I2C_EMULATED
#define SOFT_I2C_SCL PC10
#define SOFT_I2C_SDA PC11
#define I2C_DEVICE_SHARES_UART3
#define DEFAULT_I2C_BUS BUS_I2C_EMULATED
#else
// AIO
#define USE_I2C
#define DEFAULT_I2C_BUS BUS_I2C1
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define DEFAULT_I2C_BUS BUS_I2C1
#endif

View file

@ -70,7 +70,7 @@
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10

View file

@ -67,11 +67,7 @@
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
// #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_I2C_DEVICE_2
#define USE_ADC
#define ADC_CHANNEL_1_PIN PB1

View file

@ -88,12 +88,11 @@
// Enable I2C instead of PWM7&8 for iNav
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL(PWM8), PB7/SDA(PWM7)
// Because the I2C is shared with PWM7&8, there are no on-board ext. pullups.
// Turn internal pullups, they are weak, but better than nothing.
#define USE_I2C_DEVICE_1 // PB6/SCL(PWM8), PB7/SDA(PWM7)
#define USE_I2C_PULLUP
#define USE_PITOT_MS4525
#define PITOT_I2C_BUS BUS_I2C1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5

View file

@ -48,8 +48,8 @@
#endif
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C_DEVICE_SHARES_UART3
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
// MPU6000 interrupts
#define USE_EXTI
@ -109,7 +109,7 @@
#endif
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE
#define PITOT_I2C_BUS BUS_I2C2
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C2

View file

@ -163,8 +163,8 @@
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_4
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define I2C_DEVICE_SHARES_UART3
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
#define USE_BARO
#define USE_BARO_BMP280

View file

@ -145,7 +145,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define USE_I2C_PULLUP
#define I2C1_SCL PB8
#define I2C1_SDA PB9

View file

@ -97,7 +97,7 @@
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
// #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)

View file

@ -67,8 +67,7 @@
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define USE_I2C_DEVICE_2 // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL PA9
#define I2C2_SDA PA10

View file

@ -65,7 +65,7 @@
#define USE_BARO_MS5611
//#define USE_PITOT_MS4525
//#define PITOT_I2C_INSTANCE I2C_DEVICE_EXT
//#define PITOT_I2C_BUS BUS_I2C2
// #define USE_OPTICAL_FLOW
// #define USE_OPFLOW_FAKE
@ -113,8 +113,8 @@
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define I2C_DEVICE_EXT (I2CDEV_2)
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1

View file

@ -79,7 +79,7 @@
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5

View file

@ -74,8 +74,7 @@
// Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP?
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define USE_I2C_DEVICE_2
#define I2C2_SCL PA9
#define I2C2_SDA PA10

View file

@ -106,7 +106,9 @@
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
#define USE_ADC
// PC2 shared with HC-SR04

View file

@ -78,7 +78,7 @@
#define SOFTSERIAL_2_TX_PIN PB1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5

View file

@ -92,7 +92,7 @@
#endif
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)

View file

@ -89,7 +89,7 @@
#define SOFTSERIAL_1_TX_PIN PA1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_I2C_DEVICE_1
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5

View file

@ -89,7 +89,6 @@
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define USE_SPI
#define USE_SPI_DEVICE_1 // MPU

View file

@ -90,7 +90,8 @@
#define UART5_RX_PIN PD2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#if (SPRACINGF4EVO_REV >= 2)
#define I2C1_SCL PB8
#define I2C1_SDA PB9

View file

@ -92,7 +92,7 @@
#define USE_MAG_QMC5883
#define USE_PITOT_MS4525
#define PITOT_I2C_INSTANCE I2C_DEVICE
#define PITOT_I2C_BUS BUS_I2C1
#define USE_VCP
#define USE_UART1
@ -119,7 +119,7 @@
#define RX_CE_PIN PA1
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_DEVICE_1
#define USE_ADC
#define ADC_INSTANCE ADC1

View file

@ -62,7 +62,7 @@
////////////////////////
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2)
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11

View file

@ -161,6 +161,14 @@
BUSDEV_REGISTER_I2C(busdev_vl53l0x, DEVHW_VL53L0X, VL53L0X_I2C_BUS, 0x29, NONE, DEVFLAGS_NONE);
#endif
#if defined(USE_PITOT_MS4525)
#if !defined(MS4525_I2C_BUS)
#define MS4525_I2C_BUS PITOT_I2C_BUS
#endif
BUSDEV_REGISTER_I2C(busdev_ms5425, DEVHW_MS4525, MS4525_I2C_BUS, 0x28, NONE, DEVFLAGS_NONE);
#endif
#endif // USE_TARGET_HARDWARE_DESCRIPTORS