Re-enable FrSky telemetry for NAZE target
[inav/snaewe.git] / src / main / target / NAZE / target.h
blobc346b5173be89962f839c547364ba7ab17666c62
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 "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
21 #define USE_HARDWARE_REVISION_DETECTION
23 #define LED0 PB3
24 #define LED1 PB4
26 #define BEEPER PA12
27 #ifdef AFROMINI
28 #define BEEPER_INVERTED
29 #endif
31 #define BARO_XCLR_PIN PC13
32 #define BARO_EOC_PIN PC14
33 #define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
35 #define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
36 #define INVERTER_USART USART2
38 #define USE_EXTI
39 #define MAG_INT_EXTI PC14
40 #define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC
41 //#define DEBUG_MPU_DATA_READY_INTERRUPT
42 #define USE_MPU_DATA_READY_SIGNAL
43 //#define DEBUG_MAG_DATA_READY_INTERRUPT
44 #define USE_MAG_DATA_READY_SIGNAL
46 // SPI2
47 // PB15 28 SPI2_MOSI
48 // PB14 27 SPI2_MISO
49 // PB13 26 SPI2_SCK
50 // PB12 25 SPI2_NSS
52 #define USE_SPI
53 #define USE_SPI_DEVICE_2
55 #define NAZE_SPI_INSTANCE SPI2
56 #define NAZE_SPI_CS_GPIO GPIOB
57 #define NAZE_SPI_CS_PIN PB12
58 #define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
60 // We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
61 #define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
62 #define M25P16_CS_PIN NAZE_SPI_CS_PIN
63 #define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
65 #define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
66 #define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
67 #define MPU6500_CS_PIN NAZE_SPI_CS_PIN
68 #define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
70 #define USE_FLASHFS
71 #define USE_FLASH_M25P16
73 #define GYRO
74 #define USE_GYRO_MPU3050
75 #define USE_GYRO_MPU6050
76 #define USE_GYRO_MPU6500
77 #define USE_GYRO_SPI_MPU6500
79 #define GYRO_MPU3050_ALIGN CW0_DEG
80 #define GYRO_MPU6050_ALIGN CW0_DEG
81 #define GYRO_MPU6500_ALIGN CW0_DEG
83 #define ACC
84 //#define USE_ACC_ADXL345
85 //#define USE_ACC_BMA280
86 //#define USE_ACC_MMA8452
87 #define USE_ACC_MPU6050
88 #define USE_ACC_MPU6500
89 #define USE_ACC_SPI_MPU6500
91 #define ACC_ADXL345_ALIGN CW270_DEG
92 #define ACC_MPU6050_ALIGN CW0_DEG
93 #define ACC_MMA8452_ALIGN CW90_DEG
94 #define ACC_BMA280_ALIGN CW0_DEG
95 #define ACC_MPU6500_ALIGN CW0_DEG
97 #define BARO
98 #define USE_BARO_MS5611 // needed for Flip32 board
99 #define USE_BARO_BMP085
100 #define USE_BARO_BMP280
102 #define MAG
103 #define USE_MAG_HMC5883
104 //#define USE_MAG_AK8975
105 //#define USE_MAG_MAG3110
106 #define MAG_HMC5883_ALIGN CW180_DEG
108 //#define SONAR
109 //#define USE_SONAR_SRF10
110 #define SONAR_TRIGGER_PIN PB0
111 #define SONAR_ECHO_PIN PB1
112 #define SONAR_TRIGGER_PIN_PWM PB8
113 #define SONAR_ECHO_PIN_PWM PB9
115 #define USE_UART1
116 #define USE_UART2
117 #define USE_UART3
118 #define USE_SOFTSERIAL1
119 #define USE_SOFTSERIAL2
120 #define SERIAL_PORT_COUNT 5
122 #define SOFTSERIAL_1_TIMER TIM3
123 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
124 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
125 #define SOFTSERIAL_2_TIMER TIM3
126 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
127 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
129 // USART3 only on NAZE32_SP - Flex Port
130 #define UART3_RX_PIN PB11
131 #define UART3_TX_PIN PB10
133 #define USE_I2C
134 #define I2C_DEVICE (I2CDEV_2)
136 // #define SOFT_I2C // enable to test software i2c
137 // #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
138 // #define SOFT_I2C_PB67
140 //#define USE_RX_NRF24
141 #ifdef USE_RX_NRF24
143 #define USE_RX_CX10
144 #define USE_RX_H8_3D
145 #define USE_RX_REF
146 //#define USE_RX_SYMA
147 //#define USE_RX_V202
148 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
149 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_REF
150 #define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
151 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_CX10A
152 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
154 #define USE_SOFTSPI
155 #define USE_NRF24_SOFTSPI
156 // RC pinouts
157 // RC1 GND
158 // RC2 power
159 // RC3 PA0/TIM2 RX_PPM
160 // RC4 PA1/TIM2 CE / RSSI_ADC
161 // RC5 PA2/TIM2 USART2 TX
162 // RC6 PA3/TIM2 USART2 RX
163 // RC7 PA6/TIM3 CSN / softserial1 RX / LED_STRIP
164 // RC8 PA7/TIM3 SCK / softserial1 TX
165 // RC9 PB0/TIM3 MISO / softserial2 RX / sonar trigger
166 // RC10 PB1/TIM3 MOSI /softserial2 TX / sonar echo / current
168 // Nordic Semiconductor uses 'CSN', STM uses 'NSS'
169 #define NRF24_CE_PIN PA1
170 #define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
171 #define NRF24_CSN_PIN PA6
172 #define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
173 #define NRF24_SCK_PIN PA7
174 #define NRF24_MOSI_PIN PB1
175 #define NRF24_MISO_PIN PB0
176 #endif // USE_NRF24
178 #define USE_ADC
179 #define CURRENT_METER_ADC_PIN PB1
180 #define VBAT_ADC_PIN PA4
181 #define RSSI_ADC_PIN PA1
182 #define EXTERNAL1_ADC_PIN PA5
184 #define NAV
185 //#define NAV_AUTO_MAG_DECLINATION
186 #define NAV_GPS_GLITCH_DETECTION
187 #define NAV_MAX_WAYPOINTS 30
189 //#define LED_STRIP
190 #define WS2811_TIMER TIM3
191 #define WS2811_PIN PA6
192 #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
193 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
195 #define SPEKTRUM_BIND
196 // USART2, PA3
197 #define BIND_PIN PA3
199 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
201 #define TARGET_MOTOR_COUNT 6
202 #define DISABLE_UNCOMMON_MIXERS
204 #define DEFAULT_FEATURES FEATURE_VBAT
205 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM
207 // Disable HOTT and S.Port telemetry
208 #undef TELEMETRY_HOTT
209 #undef TELEMETRY_SMARTPORT
211 // Disable all GPS protocols except UBLOX
212 #undef GPS_PROTO_NMEA
213 #undef GPS_PROTO_I2C_NAV
214 #undef GPS_PROTO_NAZA
216 // IO - assuming all IOs on 48pin package
217 #define TARGET_IO_PORTA 0xffff
218 #define TARGET_IO_PORTB 0xffff
219 #define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
221 #define USABLE_TIMER_CHANNEL_COUNT 14
222 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )