[FLYWOOF411] add board documentation
[inav/snaewe.git] / src / main / target / BETAFLIGHTF4 / target.h
blobcf4727c7b3ab54ec146c73626a95226bd706e7ed
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #define TARGET_BOARD_IDENTIFIER "BFF4"
21 #define USBD_PRODUCT_STRING "BetaFlightF4"
23 //#define USE_ESC_SENSOR
25 #define LED0 PB5
27 #define BEEPER PB4
28 #define BEEPER_INVERTED
30 #define MPU6000_CS_PIN PA4
31 #define MPU6000_SPI_BUS BUS_SPI1
33 #define USE_IMU_MPU6000
34 #define IMU_MPU6000_ALIGN CW180_DEG
37 // MPU6000 interrupts
38 #define USE_EXTI
39 #define GYRO_INT_EXTI PC4
40 #define USE_MPU_DATA_READY_SIGNAL
42 #define USE_BARO
43 #define USE_BARO_BMP280
45 #define BMP280_SPI_BUS BUS_SPI2
46 #define BMP280_CS_PIN PB3
48 #define USE_OSD
49 #define USE_MAX7456
50 #define MAX7456_SPI_BUS BUS_SPI2
51 #define MAX7456_CS_PIN PB12
52 //#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz // XXX
53 //#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) // XXX
55 #define M25P16_CS_PIN PA15
56 #define M25P16_SPI_BUS BUS_SPI3
58 #define USE_FLASHFS
59 #define USE_FLASH_M25P16
61 #define USE_VCP
62 #define VBUS_SENSING_PIN PC5
63 #define VBUS_SENSING_ENABLED
65 #define USE_UART_INVERTER
67 #define USE_UART1
68 #define UART1_RX_PIN PA10
69 #define UART1_TX_PIN PA9
70 #define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
72 #define USE_UART2
73 #define UART2_RX_PIN PA3
74 #define UART2_TX_PIN PA2
75 // PC13 used as inverter select GPIO for UART2
76 #define INVERTER_PIN_UART2_RX PC13
78 #define USE_UART3
79 #define UART3_RX_PIN PB11
80 #define UART3_TX_PIN PB10
82 #define USE_UART6
83 #define UART6_RX_PIN PC7
84 #define UART6_TX_PIN PC6
86 //#define USE_SOFTSERIAL1
87 //#define USE_SOFTSERIAL2
89 #define SERIAL_PORT_COUNT 5 //VCP, USART1, USART2, USART3, USART6, SOFTSERIAL1, SOFTSERIAL2
91 //#define USE_ESCSERIAL // XXX
92 //#define ESCSERIAL_TIMER_TX_PIN PB8 // (Hardware=0, PPM)
94 #define USE_SPI
96 #define USE_SPI_DEVICE_1
97 #define SPI1_NSS_PIN NONE
98 #define SPI1_SCK_PIN PA5
99 #define SPI1_MISO_PIN PA6
100 #define SPI1_MOSI_PIN PA7
102 #define USE_SPI_DEVICE_2
103 #define SPI2_NSS_PIN PB12
104 #define SPI2_SCK_PIN PB13
105 #define SPI2_MISO_PIN PB14
106 #define SPI2_MOSI_PIN PB15
108 #define USE_SPI_DEVICE_3
109 #define SPI3_NSS_PIN PA15
110 #define SPI3_SCK_PIN PC10
111 #define SPI3_MISO_PIN PC11
112 #define SPI3_MOSI_PIN PC12
114 #define USE_I2C
115 #define USE_I2C_DEVICE_2
116 #define I2C2_SCL PB10 // PB10, UART3_TX
117 #define I2C2_SDA PB11 // PB11, UART3_RX
118 //#define I2C_DEVICE (I2CDEV_2)
120 #define USE_MAG
121 #define MAG_I2C_BUS BUS_I2C2
122 //#define MAG_HMC5883_ALIGN CW90_DEG
123 #define USE_MAG_AK8963
124 #define USE_MAG_AK8975
125 #define USE_MAG_HMC5883
126 #define USE_MAG_QMC5883
127 #define USE_MAG_IST8310
128 #define USE_MAG_IST8308
129 #define USE_MAG_MAG3110
130 #define USE_MAG_LIS3MDL
132 #define TEMPERATURE_I2C_BUS BUS_I2C2
134 #define USE_BARO
135 #define BARO_I2C_BUS BUS_I2C2
136 #define USE_BARO_BMP085
137 #define USE_BARO_BMP280
138 #define USE_BARO_MS5611
140 #define USE_PITOT_ADC
141 #define PITOT_I2C_BUS BUS_I2C2
143 #define USE_RANGEFINDER
144 #define RANGEFINDER_I2C_BUS BUS_I2C2
145 #define USE_RANGEFINDER_HCSR04_I2C
147 #define USE_ADC
148 #define ADC_CHANNEL_1_PIN PC1
149 #define ADC_CHANNEL_2_PIN PC2
150 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
151 #define VBAT_ADC_CHANNEL ADC_CHN_2
153 #define USE_LED_STRIP
154 #define WS2811_PIN PB6
156 #define SERIALRX_PROVIDER SERIALRX_SBUS
157 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL
158 #define SERIALRX_UART SERIAL_PORT_USART6
160 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
161 #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_OSD )
163 #define USE_SPEKTRUM_BIND
164 // USART3,
165 #define BIND_PIN PB11
167 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
169 #define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
170 #define TARGET_IO_PORTB (0xffff & ~(BIT(2)))
171 #define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)))
172 #define TARGET_IO_PORTD BIT(2)
174 #define MAX_PWM_OUTPUT_PORTS 4
176 #define PCA9685_I2C_BUS BUS_I2C2
178 #define USE_DSHOT
179 #define USE_ESC_SENSOR