Boot-time event logging implementation (#536)
[betaflight.git] / src / main / target / CC3D / target.h
blobd059314daadb7c03fe496790e4a4bede217c00c8
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 #define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
20 #define LED0 PB3
22 #define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
23 #define INVERTER_USART USART1
25 #define BEEPER PB15
26 #define BEEPER_OPT PB2
28 #define USE_EXTI
29 #define MPU_INT_EXTI PA3
30 #define USE_MPU_DATA_READY_SIGNAL
31 //#define DEBUG_MPU_DATA_READY_INTERRUPT
33 #define USE_SPI
34 #define USE_SPI_DEVICE_1
35 #define USE_SPI_DEVICE_2
37 #define USE_I2C
38 #define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
40 #define MPU6000_CS_PIN PA4
41 #define MPU6000_SPI_INSTANCE SPI1
43 #define M25P16_CS_PIN PB12
44 #define M25P16_SPI_INSTANCE SPI2
46 #define USE_FLASHFS
47 #define USE_FLASH_M25P16
49 #define GYRO
50 #define USE_GYRO_SPI_MPU6000
51 #define GYRO_MPU6000_ALIGN CW270_DEG
53 #define ACC
54 #define USE_ACC_SPI_MPU6000
55 #define ACC_MPU6000_ALIGN CW270_DEG
57 // External I2C BARO
58 #define BARO
59 //#define USE_BARO_MS5611
60 #define USE_BARO_BMP085
61 #define USE_BARO_BMP280
63 // External I2C MAG
64 #define MAG
65 #define USE_MAG_HMC5883
66 //#define USE_MAG_AK8975
67 //#define USE_MAG_MAG3110
69 #define USE_VCP
70 #define USE_UART1
71 #define USE_UART3
73 #define UART3_RX_PIN PB11
74 #define UART3_TX_PIN PB10
77 #if defined(CC3D_NRF24) || defined(CC3D_NRF24_OPBL)
78 #define USE_RX_NRF24
79 #endif
81 #ifdef USE_RX_NRF24
82 #define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
83 #define DEFAULT_FEATURES FEATURE_SOFTSPI
84 #define USE_RX_SYMA
85 //#define USE_RX_V202
86 #define USE_RX_CX10
87 //#define USE_RX_H8_3D
88 #define USE_RX_INAV
89 #define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
90 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
91 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
93 #define USE_SOFTSPI
94 #define USE_NRF24_SOFTSPI
96 // RC pinouts
97 // RC1 GND
98 // RC2 power
99 // RC3 PB6/TIM4 unused
100 // RC4 PB5/TIM3 SCK / softserial1 TX / sonar trigger
101 // RC5 PB0/TIM3 MISO / softserial1 RX / sonar echo / RSSI ADC
102 // RC6 PB1/TIM3 MOSI / current
103 // RC7 PA0/TIM2 CSN / battery voltage
104 // RC8 PA1/TIM2 CE / RX_PPM
106 // Nordic Semiconductor uses 'CSN', STM uses 'NSS'
107 #define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
108 #define NRF24_CSN_PIN PA0
109 #define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
110 #define NRF24_CE_PIN PA1
111 #define NRF24_CSN_PIN PA0
112 #define NRF24_SCK_PIN PB5
113 #define NRF24_MOSI_PIN PB1
114 #define NRF24_MISO_PIN PB0
116 #define SERIAL_PORT_COUNT 3
118 #else
120 #define USE_SOFTSERIAL1
121 #define SERIAL_PORT_COUNT 4
123 #ifdef USE_UART1_RX_DMA
124 #undef USE_UART1_RX_DMA
125 #endif
127 #define SOFTSERIAL_1_TIMER TIM3
128 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
129 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
131 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM
133 #endif // USE_RX_NRF24
136 #define USE_ADC
137 #define CURRENT_METER_ADC_PIN PB1
138 #define VBAT_ADC_PIN PA0
139 #ifdef CC3D_PPM1
140 #define RSSI_ADC_PIN PA1
141 #else
142 #define RSSI_ADC_PIN PB0
143 #endif
145 // LED strip is on PWM5 output pin
146 //#define LED_STRIP
147 #define WS2811_PIN PB4
148 #define WS2811_TIMER TIM3
149 #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
150 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
152 #define SPEKTRUM_BIND
153 // USART3, PB11 (Flexport)
154 #define BIND_PIN PB11
156 //#define USE_SERIAL_4WAY_BLHELI_INTERFACE
158 //#define SONAR
159 //#define USE_SONAR_SRF10
160 #define SONAR_ECHO_PIN PB0
161 #define SONAR_TRIGGER_PIN PB5
163 #define NAV
164 //#define NAV_AUTO_MAG_DECLINATION
165 //#define NAV_GPS_GLITCH_DETECTION
166 #define NAV_MAX_WAYPOINTS 30
168 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
170 #undef TELEMETRY_FRSKY
171 #undef TELEMETRY_HOTT
172 #undef TELEMETRY_SMARTPORT
174 #undef GPS_PROTO_NMEA
175 #undef GPS_PROTO_NAZA
176 #undef GPS_PROTO_I2C_NAV
178 #ifdef OPBL
180 #ifdef USE_RX_NRF24
181 #undef USE_SERVOS
182 #undef USE_SONAR
183 #else
184 #undef USE_SONAR_SRF10
185 #endif // USE_RX_NRF24
187 #define TARGET_MOTOR_COUNT 4
188 #undef USE_MAG_AK8975
189 #undef USE_MAG_MAG3110
190 #undef BLACKBOX
191 #undef SERIAL_RX
192 #undef SPEKTRUM_BIND
194 #else
195 #define TARGET_MOTOR_COUNT 4
196 #define DISABLE_UNCOMMON_MIXERS
197 #endif //OPBL
200 #define SKIP_RX_MSP
201 #ifdef USE_RX_NRF24
202 #define SKIP_RX_PWM_PPM
203 #undef SERIAL_RX
204 #undef SPEKTRUM_BIND
205 #undef TELEMETRY
206 #undef TELEMETRY_LTM
207 #endif
209 // Number of available PWM outputs
210 #define MAX_PWM_OUTPUT_PORTS 11
212 // DEBUG
213 //#define USE_ASSERT // include assertion support code
214 //#define USE_ASSERT_FULL // Provide file information
215 //#define USE_ASSERT_STOP // stop on failed assertion
216 //#define USE_ASSERT_CHECK // include assertion check code (should in general a per-file define)
218 //#define HIL
219 //#define USE_FAKE_MAG
220 //#define USE_FAKE_BARO
221 //#define USE_FAKE_GPS
223 // IO - from schematics
224 #define TARGET_IO_PORTA 0xffff
225 #define TARGET_IO_PORTB 0xffff
226 #define TARGET_IO_PORTC ( BIT(14) )
228 #define USABLE_TIMER_CHANNEL_COUNT 12
229 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )