Ensure that we don't initialise more motors than are defined in target.h. Make MAX_PW...
[betaflight.git] / src / main / target / CJMCU / target.h
blob2c71de593445b2a9d413823c7ce19b873958d0ee
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 PC14
24 #define LED1 PC13
25 #define LED2 PC15
27 #undef BEEPER
29 #define GYRO
30 #define USE_GYRO_MPU6050
32 #define ACC
33 #define USE_ACC_MPU6050
35 //#define MAG
36 //#define USE_MAG_HMC5883
38 #define USE_UART1
39 #define USE_UART2
40 #define SERIAL_PORT_COUNT 2
42 #define USE_I2C
43 #define I2C_DEVICE (I2CDEV_1)
45 #define USE_SPI
46 #define USE_SPI_DEVICE_1
48 #define USE_RX_NRF24
49 #ifdef USE_RX_NRF24
51 #define NRF24_SPI_INSTANCE SPI1
52 #define USE_NRF24_SPI1
54 // Nordic Semiconductor uses 'CSN', STM uses 'NSS'
55 #define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
56 #define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
57 #define NRF24_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
58 #define NRF24_CE_PIN PA4
59 #define NRF24_CSN_PIN PA11
60 #define NRF24_SCK_PIN PA5
61 #define NRF24_MISO_PIN PA6
62 #define NRF24_MOSI_PIN PA7
63 #define NRF24_IRQ_PIN PA8
64 // CJMCU has NSS on PA11, rather than the standard PA4
65 #define SPI1_NSS_PIN NRF24_CSN_PIN
66 #define SPI1_SCK_PIN NRF24_SCK_PIN
67 #define SPI1_MISO_PIN NRF24_MISO_PIN
68 #define SPI1_MOSI_PIN NRF24_MOSI_PIN
70 #define USE_RX_NRF24
71 #define USE_RX_CX10
72 #define USE_RX_H8_3D
73 #define USE_RX_INAV
74 //#define USE_RX_SYMA
75 //#define USE_RX_V202
76 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
77 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_INAV
78 #define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
79 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_CX10A
80 //#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
81 //#define DEBUG_NRF24_INAV
83 #define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
84 #define TELEMETRY_LTM
85 #define TELEMETRY_NRF24_LTM
86 #define SKIP_RX_PWM_PPM
87 #undef SERIAL_RX
88 #undef SKIP_TASK_STATISTICS
90 #else
92 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM
93 #undef SKIP_RX_MSP
95 #define SPEKTRUM_BIND
96 // UART2, PA3
97 #define BIND_PIN PA3
98 #endif //USE_RX_NRF24
100 #define BRUSHED_MOTORS
101 #define DEFAULT_FEATURES FEATURE_MOTOR_STOP
102 #define SKIP_SERIAL_PASSTHROUGH
104 // Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
105 #define USE_QUAD_MIXER_ONLY
106 #undef USE_SERVOS
108 #if (FLASH_SIZE <= 64)
109 #undef BLACKBOX
110 #endif
112 // Number of available PWM outputs
113 #define MAX_PWM_OUTPUT_PORTS 4
115 // IO - assuming all IOs on 48pin package TODO
116 #define TARGET_IO_PORTA 0xffff
117 #define TARGET_IO_PORTB 0xffff
118 #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
120 #define USABLE_TIMER_CHANNEL_COUNT 14
121 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))