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/>.
20 #define TARGET_BOARD_IDENTIFIER "MOTO" // MotoLab
22 #define LED0 PB5 // Blue LEDs - PB5
23 #define LED1 PB9 // Green LEDs - PB9
26 #define BEEPER_INVERTED
30 #define GYRO_INT_EXTI PA15
31 #define USE_MPU_DATA_READY_SIGNAL
33 #define USE_IMU_MPU6050
34 #define IMU_MPU6050_ALIGN CW180_DEG
36 #define USE_IMU_MPU6000
37 #define IMU_MPU6000_ALIGN CW180_DEG
39 #define MPU6050_I2C_BUS BUS_I2C2
40 #define MPU6000_CS_PIN PB12
41 #define MPU6000_SPI_BUS BUS_SPI2
44 //#define USE_BARO_MS5611
47 //#define USE_MAG_HMC5883
48 //#define USE_MAG_QMC5883
49 //#define USE_MAG_IST8310
50 //#define USE_MAG_IST8308
51 //#define USE_MAG_MAG3110
52 //#define USE_MAG_LIS3MDL
58 #define SERIAL_PORT_COUNT 4
60 #define UART1_TX_PIN PB6
61 #define UART1_RX_PIN PB7
63 #define UART2_TX_PIN PB3
64 #define UART2_RX_PIN PB4
66 #define UART3_TX_PIN PB10 // PB10 (AF7)
67 #define UART3_RX_PIN PB11 // PB11 (AF7)
70 #define USE_I2C_DEVICE_2
75 #define USE_SPI_DEVICE_2
77 #define M25P16_CS_PIN PB12
78 #define M25P16_SPI_BUS BUS_SPI2
80 //#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
81 #define SENSORS_SET (SENSOR_ACC)
84 #define USE_FLASH_M25P16
86 #define BOARD_HAS_VOLTAGE_DIVIDER
88 #define ADC_INSTANCE ADC2
89 #define ADC_CHANNEL_1_PIN PA5
90 #define ADC_CHANNEL_2_PIN PB2
91 #define VBAT_ADC_CHANNEL ADC_CHN_1
92 #define RSSI_ADC_CHANNEL ADC_CHN_2
96 #define USE_LED_STRIP_ON_DMA1_CHANNEL3
97 #define WS2811_PIN PB8 // TIM16_CH1
100 #define USE_SPEKTRUM_BIND
104 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
107 #undef USE_GPS_PROTO_NMEA
108 //#undef USE_GPS_PROTO_UBLOX
109 #undef USE_GPS_PROTO_I2C_NAV
110 #undef USE_GPS_PROTO_NAZA
112 // Number of available PWM outputs
113 #define MAX_PWM_OUTPUT_PORTS 8
115 // IO - stm32f303cc in 48pin package
116 #define TARGET_IO_PORTA 0xffff
117 #define TARGET_IO_PORTB 0xffff
118 #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
119 // #define TARGET_IO_PORTF (BIT(0)|BIT(1))
120 // !!TODO - check the following line is correct
121 #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
123 #define PCA9685_I2C_BUS BUS_I2C2