SPRACINGF4EVO - Initial target support
[betaflight.git] / src / main / target / SPRACINGF4EVO / target.h
blob8427804efd16722d4385e15abf9b8498f167e205
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 "SP4E"
21 #define TARGET_CONFIG
23 #ifndef SPRACINGF4EVO_REV
24 #define SPRACINGF4EVO_REV 2
25 #endif
27 #define USBD_PRODUCT_STRING "SP Racing F4 NEO"
29 #define LED0 PA0
31 #define BEEPER PC15
32 #define BEEPER_INVERTED
34 #define INVERTER_PIN_UART2 PB2
36 #define USE_EXTI
37 #define MPU_INT_EXTI PC13
39 #define USE_MPU_DATA_READY_SIGNAL
40 #define ENSURE_MPU_DATA_READY_IS_LOW
42 #define USE_MAG_DATA_READY_SIGNAL
43 #define ENSURE_MAG_DATA_READY_IS_HIGH
45 #define GYRO
46 #define USE_GYRO_SPI_MPU6500
48 #define ACC
49 #define USE_ACC_SPI_MPU6500
51 #define ACC_MPU6500_ALIGN CW0_DEG
52 #define GYRO_MPU6500_ALIGN CW0_DEG
54 #define BARO
55 #define USE_BARO_BMP280
56 #define USE_BARO_MS5611
58 #define MAG
59 #define USE_MAG_AK8975
60 #define USE_MAG_HMC5883
62 #define USB_IO
64 #define USE_VCP
65 #define USE_UART1
66 #define USE_UART2
67 #define USE_UART3
68 #define USE_UART4
69 #define USE_UART5
70 #define SERIAL_PORT_COUNT 6
72 #define UART1_TX_PIN PA9
73 #define UART1_RX_PIN PA10
75 #define UART2_TX_PIN PA2
76 #define UART2_RX_PIN PA3
78 #define UART3_TX_PIN PB10
79 #define UART3_RX_PIN PB11
81 #define UART4_TX_PIN PC10
82 #define UART4_RX_PIN PC11
84 #define UART5_TX_PIN PC12
85 #define UART5_RX_PIN PD2
87 // TODO
88 // #define USE_ESCSERIAL
89 // #define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
91 #define USE_I2C
92 #define I2C_DEVICE (I2CDEV_1)
93 #if (SPRACINGF4EVO_REV >= 2)
94 #define I2C1_SCL PB8
95 #define I2C1_SDA PB9
96 #else
97 #define I2C1_SCL PB6
98 #define I2C1_SDA PB7
99 #endif
101 #define USE_SPI
102 #define USE_SPI_DEVICE_1 // MPU
103 #define USE_SPI_DEVICE_2 // SDCard
104 #define USE_SPI_DEVICE_3 // External
106 #define SPI1_NSS_PIN PA4
107 #define SPI1_SCK_PIN PA5
108 #define SPI1_MISO_PIN PA6
109 #define SPI1_MOSI_PIN PA7
111 #define SPI2_NSS_PIN PB12
112 #define SPI2_SCK_PIN PB13
113 #define SPI2_MISO_PIN PB14
114 #define SPI2_MOSI_PIN PB15
116 #define SPI3_NSS_PIN PA15 // NC
117 #define SPI3_SCK_PIN PB3 // NC
118 #define SPI3_MISO_PIN PB4 // NC
119 #define SPI3_MOSI_PIN PB5 // NC
121 #define USE_SDCARD
122 #define USE_SDCARD_SPI2
124 #define SDCARD_DETECT_INVERTED
126 #define SDCARD_DETECT_PIN PC14
127 #define SDCARD_SPI_INSTANCE SPI2
128 #define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
130 // SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
131 #define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
132 // Divide to under 25MHz for normal operation:
133 #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
135 #define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
136 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
137 #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
138 #define SDCARD_DMA_CHANNEL DMA_Channel_0
141 #define MPU6500_CS_PIN SPI1_NSS_PIN
142 #define MPU6500_SPI_INSTANCE SPI1
144 #define USE_ADC
145 #define ADC_INSTANCE ADC1
146 #define ADC1_DMA_STREAM DMA2_Stream0
148 #define VBAT_ADC_PIN PC1
149 #define CURRENT_METER_ADC_PIN PC2
150 #define RSSI_ADC_PIN PC0
152 // PC4 - NC - Free for ADC12_IN14 / VTX CS
153 // PC5 - NC - Free for ADC12_IN15 / VTX Enable / OSD VSYNC
155 #define BOARD_HAS_VOLTAGE_DIVIDER
158 #define LED_STRIP
159 #define TRANSPONDER
161 #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
163 #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
164 #define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
165 #define SERIALRX_UART SERIAL_PORT_USART2
166 #define TELEMETRY_UART SERIAL_PORT_UART5
167 #define SERIALRX_PROVIDER SERIALRX_SBUS
169 #define SPEKTRUM_BIND_PIN UART2_RX_PIN
171 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
173 #define TARGET_IO_PORTA 0xffff
174 #define TARGET_IO_PORTB 0xffff
175 #define TARGET_IO_PORTC 0xffff
176 #define TARGET_IO_PORTD (BIT(2))
178 #define USABLE_TIMER_CHANNEL_COUNT 16 // 4xPWM, 8xESC, 2xESC via UART3 RX/TX, 1xLED Strip, 1xIR.
179 #if (SPRACINGF4NEO_REV >= 2)
180 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9))
181 #else
182 #define USE_TIM10_TIM11_FOR_MOTORS
183 #ifdef USE_TIM10_TIM11_FOR_MOTORS
184 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11))
185 #else
186 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9))
187 #endif
188 #endif