CJMCU - Disable gyro sync by default on as the MPU INT signal is not
[betaflight.git] / src / main / target / CJMCU / target.h
blob21a94e93eadcac39d356fb36c109a75beace8aad
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 "CJM1" // CJMCU
21 #define USE_HARDWARE_REVISION_DETECTION
23 #define LED0_GPIO GPIOC
24 #define LED0_PIN Pin_14 // PC14 (LED)
25 #define LED0
26 #define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
27 #define LED1_GPIO GPIOC
28 #define LED1_PIN Pin_13 // PC13 (LED)
29 #define LED1
30 #define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
31 #define LED2_GPIO GPIOC
32 #define LED2_PIN Pin_15 // PC15 (LED)
33 #define LED2
34 #define LED2_PERIPHERAL RCC_APB2Periph_GPIOC
37 #define ACC
38 #define USE_ACC_MPU6050
40 #define GYRO
41 #define USE_GYRO_MPU6050
43 #define DEFAULT_GYRO_SYNC 0
45 #define MAG
46 #define USE_MAG_HMC5883
48 #define BRUSHED_MOTORS
50 #define USE_UART1
51 #define USE_UART2
53 #define SERIAL_PORT_COUNT 2
55 #define USE_UART1_TX_DMA
57 #define USE_I2C
58 #define I2C_DEVICE (I2CDEV_1)
60 // #define SOFT_I2C // enable to test software i2c
61 // #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
62 // #define SOFT_I2C_PB67
64 #if (FLASH_SIZE > 64)
65 #define USE_ADC
67 #define ADC_INSTANCE ADC1
68 #define ADC_ABP2_PERIPHERAL RCC_APB2Periph_ADC1
69 #define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
70 #define ADC_DMA_CHANNEL DMA1_Channel1
72 #define ADC0_GPIO GPIOA
73 #define ADC0_GPIO_PIN GPIO_Pin_4
74 #define ADC0_CHANNEL ADC_Channel_4
76 #define ADC_CHANNEL_COUNT 1
78 #define ADC_BATTERY ADC_CHANNEL1
79 #endif
81 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM
83 #define SERIAL_RX
84 #define USE_CLI
86 #define SPEKTRUM_BIND
87 // UART2, PA3
88 #define BIND_PORT GPIOA
89 #define BIND_PIN Pin_3
91 // Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
92 #define USE_QUAD_MIXER_ONLY
95 #if (FLASH_SIZE > 64)
96 #define BLACKBOX
97 #define GTUNE
98 #else
99 #define SKIP_3D_FLIGHT
100 #define SKIP_SERIAL_PASSTHROUGH
101 #define SKIP_TASK_STATISTICS
102 #define SKIP_CLI_FRILLS
103 #define SKIP_CLI_STATUS
104 #define SKIP_CLI_COMMAND_HELP
105 #define SKIP_PID_MWREWRITE
106 #define SKIP_PID_MW23
107 #define SKIP_BOARD_ALIGNMENT // CJMCU only has one alignment.
108 #define SKIP_SERIAL_PASSTHROUGH
110 #endif
113 // IO - assuming all IOs on 48pin package TODO
114 #define TARGET_IO_PORTA 0xffff
115 #define TARGET_IO_PORTB 0xffff
116 #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))