Fixed CONFIG_FASTLOOP_PREFERRED_ACC related magic numbers
[betaflight.git] / src / main / target / ALIENFLIGHTF3 / target.h
blob23c4a59199bdf191a91427d7ad703b88c5ee4bef
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 "AFF3" // AlienFlight F3.
21 #define ALIENFLIGHT
23 #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
25 #define USE_HARDWARE_REVISION_DETECTION
26 #define HW_PIN PB2
28 // LED's V1
29 #define LED0 PB4 // LED - PB4
30 #define LED1 PB5 // LED - PB5
32 // LED's V2
33 #define LED0_A PB8 // LED - PB8
34 #define LED1_A PB9 // LED - PB9
36 #define BEEPER PA5 // LED - PA5
38 #define USABLE_TIMER_CHANNEL_COUNT 11
40 #define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
42 #define USE_EXTI
43 //#define DEBUG_MPU_DATA_READY_INTERRUPT
44 #define USE_MPU_DATA_READY_SIGNAL
46 // Using MPU6050 for the moment.
47 #define GYRO
48 #define USE_GYRO_MPU6050
49 #define USE_GYRO_MPU6500
50 #define USE_GYRO_SPI_MPU6500
52 #define GYRO_MPU6050_ALIGN CW270_DEG
53 #define GYRO_MPU6500_ALIGN CW270_DEG
55 #define ACC
56 #define USE_ACC_MPU6050
57 #define USE_ACC_MPU6500
58 #define USE_ACC_SPI_MPU6500
60 #define ACC_MPU6050_ALIGN CW270_DEG
61 #define ACC_MPU6500_ALIGN CW270_DEG
63 // No baro support.
64 //#define BARO
65 //#define USE_BARO_MS5611
67 // option to use MPU9150 or MPU9250 integrated AK89xx Mag
68 #define MAG
69 #define USE_MAG_AK8963
71 #define MAG_AK8963_ALIGN CW0_DEG_FLIP
73 #define USE_VCP
74 #define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
75 #define USE_USART2 // Receiver - RX (PA3)
76 #define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
77 #define SERIAL_PORT_COUNT 4
79 #define UART1_TX_PIN GPIO_Pin_6 // PB6
80 #define UART1_RX_PIN GPIO_Pin_7 // PB7
81 #define UART1_GPIO GPIOB
82 #define UART1_GPIO_AF GPIO_AF_7
83 #define UART1_TX_PINSOURCE GPIO_PinSource6
84 #define UART1_RX_PINSOURCE GPIO_PinSource7
86 #define UART2_TX_PIN GPIO_Pin_2 // PA2
87 #define UART2_RX_PIN GPIO_Pin_3 // PA3
88 #define UART2_GPIO GPIOA
89 #define UART2_GPIO_AF GPIO_AF_7
90 #define UART2_TX_PINSOURCE GPIO_PinSource2
91 #define UART2_RX_PINSOURCE GPIO_PinSource3
93 #define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
94 #define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
95 #define UART3_GPIO_AF GPIO_AF_7
96 #define UART3_GPIO GPIOB
97 #define UART3_TX_PINSOURCE GPIO_PinSource10
98 #define UART3_RX_PINSOURCE GPIO_PinSource11
101 #define USE_I2C
102 #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
104 #define I2C2_SCL_PIN PA9
105 #define I2C2_SDA_PIN PA10
107 // SPI3
108 // PA15 38 SPI3_NSS
109 // PB3 39 SPI3_SCK
110 // PB4 40 SPI3_MISO
111 // PB5 41 SPI3_MOSI
113 #define USE_SPI
114 #define USE_SPI_DEVICE_3
116 #define MPU6500_CS_PIN PA15
117 #define MPU6500_SPI_INSTANCE SPI3
119 #define USE_ADC
121 #define ADC_INSTANCE ADC2
122 #define ADC_DMA_CHANNEL DMA2_Channel1
123 #define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
125 //#define BOARD_HAS_VOLTAGE_DIVIDER
127 #define VBAT_ADC_GPIO GPIOA
128 #define VBAT_ADC_GPIO_PIN GPIO_Pin_4
129 #define VBAT_ADC_CHANNEL ADC_Channel_1
131 #undef BLACKBOX
132 #undef GPS
133 #undef DISPLAY
134 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM
135 #define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP)
137 #define SPEKTRUM_BIND
138 // USART2, PA3
139 #define BIND_PIN PA3
141 // alternative defaults for AlienFlight F3 target
142 #define ALIENFLIGHT
143 #define HARDWARE_BIND_PLUG
145 // Hardware bind plug at PB12 (Pin 25)
146 #define BINDPLUG_PIN PB12
148 // IO - assuming 303 in 64pin package, TODO
149 #define TARGET_IO_PORTA 0xffff
150 #define TARGET_IO_PORTB 0xffff
151 #define TARGET_IO_PORTC 0xffff
152 #define TARGET_IO_PORTD (BIT(2))
153 #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
156 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
158 #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
159 #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17)
160 #define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)