mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
CC3D - Use Flex port in I2C mode unless USART3 is used. Add I2C drivers
for compass, baro and display.
This commit is contained in:
parent
ce0a93a5d8
commit
9e73dca591
4 changed files with 39 additions and 2 deletions
5
Makefile
5
Makefile
|
@ -381,7 +381,12 @@ CC3D_SRC = \
|
||||||
drivers/accgyro_spi_mpu6000.c \
|
drivers/accgyro_spi_mpu6000.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/adc_stm32f10x.c \
|
drivers/adc_stm32f10x.c \
|
||||||
|
drivers/barometer_bmp085.c \
|
||||||
|
drivers/barometer_ms5611.c \
|
||||||
drivers/bus_spi.c \
|
drivers/bus_spi.c \
|
||||||
|
drivers/bus_i2c_stm32f10x.c \
|
||||||
|
drivers/compass_hmc5883l.c \
|
||||||
|
drivers/display_ug2864hsweg01.c \
|
||||||
drivers/gpio_stm32f10x.c \
|
drivers/gpio_stm32f10x.c \
|
||||||
drivers/inverter.c \
|
drivers/inverter.c \
|
||||||
drivers/light_led_stm32f10x.c \
|
drivers/light_led_stm32f10x.c \
|
||||||
|
|
|
@ -79,6 +79,22 @@ The SoftSerial port is not available when RX_PARALLEL_PWM is used. The transmiss
|
||||||
|
|
||||||
To connect the GUI to the flight controller you need additional hardware attached to the USART1 serial port (by default).
|
To connect the GUI to the flight controller you need additional hardware attached to the USART1 serial port (by default).
|
||||||
|
|
||||||
|
# Flex Port
|
||||||
|
|
||||||
|
The flex port will be enabled in I2C mode unless USART3 is used. You can connect external I2C sensors and displays to this port.
|
||||||
|
|
||||||
|
You cannot use USART3 and I2C at the same time.
|
||||||
|
|
||||||
|
## Flex port pinout
|
||||||
|
|
||||||
|
| Pin | Signal | Notes |
|
||||||
|
| --- | ------------------ | ----------------------- |
|
||||||
|
| 1 | GND | |
|
||||||
|
| 2 | VCC unregulated | |
|
||||||
|
| 3 | I2C SCL / UART3 TX | 3.3v level |
|
||||||
|
| 4 | I2C SDA / UART3 RX | 3.3v level (5v tolerant |
|
||||||
|
|
||||||
|
|
||||||
# Flashing
|
# Flashing
|
||||||
|
|
||||||
There are two primary ways to get Cleanflight onto a CC3D board.
|
There are two primary ways to get Cleanflight onto a CC3D board.
|
||||||
|
|
|
@ -206,12 +206,15 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_I2C
|
#ifdef USE_I2C
|
||||||
#ifdef NAZE
|
#if defined(NAZE)
|
||||||
if (hardwareRevision != NAZE32_SP) {
|
if (hardwareRevision != NAZE32_SP) {
|
||||||
i2cInit(I2C_DEVICE);
|
i2cInit(I2C_DEVICE);
|
||||||
}
|
}
|
||||||
|
#elif defined(CC3D)
|
||||||
|
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
}
|
||||||
#else
|
#else
|
||||||
// Configure the rest of the stuff
|
|
||||||
i2cInit(I2C_DEVICE);
|
i2cInit(I2C_DEVICE);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -47,8 +47,18 @@
|
||||||
|
|
||||||
#define ACC_SPI_MPU6000_ALIGN CW270_DEG
|
#define ACC_SPI_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
// External I2C BARO
|
||||||
|
#define BARO
|
||||||
|
#define USE_BARO_MS5611
|
||||||
|
#define USE_BARO_BMP085
|
||||||
|
|
||||||
|
// External I2C MAG
|
||||||
|
#define MAG
|
||||||
|
#define USE_MAG_HMC5883
|
||||||
|
|
||||||
#define INVERTER
|
#define INVERTER
|
||||||
#define BEEPER
|
#define BEEPER
|
||||||
|
#define DISPLAY
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
#define USE_USART3
|
#define USE_USART3
|
||||||
|
@ -69,6 +79,9 @@
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
||||||
|
#define USE_I2C
|
||||||
|
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define CURRENT_METER_ADC_GPIO GPIOB
|
#define CURRENT_METER_ADC_GPIO GPIOB
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue