STM32F4: Targets

This commit is contained in:
blckmn 2016-06-08 05:38:55 +10:00
parent 49c0b2b5bf
commit 6bf35e09ce
9 changed files with 998 additions and 5 deletions

View File

@ -50,12 +50,12 @@ SDCARD_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 SPRACINGF3MINI AQ32_V2
SPRACINGF3_TARGETS = RMDO IRCFUSIONF3
SERIAL_USB_TARGETS = SPRACINGF3 IRCFUSIONF3
# Valid targets for OP VCP support
VCP_VALID_TARGETS = BLUEJAYF4 $(CC3D_TARGETS)
# Valid targets for STM VCP support
VCP_VALID_TARGETS = KKNGF4 REVO BLUEJAYF4 $(CC3D_TARGETS)
F405_TARGETS = REVO REVO_OPBL SPARKY2 ALIENFLIGHTF4 BLUEJAYF4 VRCORE QUANTON AQ32_V2 KKNGF4
F405_TARGETS_16 = QUANTON
F411_TARGETS = REVONANO
F405_TARGETS = REVO ALIENFLIGHTF4 BLUEJAYF4 KKNGF4
F405_TARGETS_16 =
F411_TARGETS =
F1_TARGETS = NAZE OLIMEXINO $(CC3D_TARGETS) PORT103R ALIENFLIGHTF1 AFROMINI
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY
@ -925,6 +925,23 @@ BLUEJAYF4_SRC = \
$(COMMON_SRC) \
$(VCPF4_SRC)
REVO_SRC = \
$(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
KKNGF4_SRC = \
$(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src

View File

@ -0,0 +1,90 @@
#include <stdbool.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2
PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3
PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4
PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6
PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // servo #7
PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #9
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2
PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3
PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4
PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5
PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM1}, // PWM1 - PA8 RC1
{ TIM1, GPIOB, Pin_0, TIM_Channel_2, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM1}, // PWM2 - PB0 RC2
{ TIM1, GPIOB, Pin_1, TIM_Channel_3, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM1}, // PWM3 - PB1 RC3
{ TIM8, GPIOB, Pin_14, TIM_Channel_2, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM8}, // PWM4 - PA14 RC4
{ TIM8, GPIOB, Pin_15, TIM_Channel_3, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource15, GPIO_AF_TIM8}, // PWM5 - PA15 RC5
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM4}, // PWM6 - PB8 OUT1
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM4}, // PWM7 - PB9 OUT2
{ TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5}, // PWM8 - PA0 OUT3
{ TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM5}, // PWM9 - PA1 OUT4
{ TIM3, GPIOC, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource6, GPIO_AF_TIM3}, // PWM10 - PC6 OUT5
{ TIM3, GPIOC, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource7, GPIO_AF_TIM3}, // PWM11 - PC7 OUT6
{ TIM3, GPIOC, Pin_8, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM3}, // PWM13 - PC8 OUT7
{ TIM3, GPIOC, Pin_9, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM3}, // PWM13 - PC9 OUT8
};

View File

@ -0,0 +1,216 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_MSP_PORT 1
#define CONFIG_RX_SERIAL_PORT 2
#define USBD_PRODUCT_STRING "AlienFlight F4"
#define LED0 PC12
#define LED1 PD2
#define BEEPER PC13
#define INVERTER PC15
#define INVERTER_USART USART2
// MPU interrupt
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define MPU_INT_EXTI PC14
#define USE_EXTI
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU9250_CS_PIN PA4
#define MPU9250_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6500
//#define USE_ACC_SPI_MPU9250
#define ACC_MPU6500_ALIGN CW270_DEG
#define ACC_MPU9250_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6500
#define USE_GYRO_SPI_MPU9250
#define GYRO_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU9250_ALIGN CW270_DEG
#define MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8963
#define MAG_HMC5883_ALIGN CW180_DEG
#define MAG_AK8963_ALIGN CW270_DEG
#define BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP280
#define USE_SDCARD
//#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB10
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
//#define M25P16_CS_PIN SPI2_NSS_PIN
//#define M25P16_SPI_INSTANCE SPI2
//#define USE_FLASHFS
//#define USE_FLASH_M25P16
#define USABLE_TIMER_CHANNEL_COUNT 13
#define USE_VCP
#define USE_USART1
#define USART1_RX_PIN PA10
#define USART1_TX_PIN PA9
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_USART2
#define USART2_RX_PIN PA3
#define USART2_TX_PIN PA2 //inverter
//#define USE_USART3
//#define USART3_RX_PIN PB11
//#define USART3_TX_PIN PB10
#define USE_USART4
#define USART4_RX_PIN PC10
#define USART4_TX_PIN PC11
//#define USE_USART5
//#define USART5_RX_PIN PD2
//#define USART5_TX_PIN PC12
#define SERIAL_PORT_COUNT 4
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC3
#define USE_SPI_DEVICE_3
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
//#define I2C_DEVICE_EXT (I2CDEV_2)
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_ADC
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC0
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_PIN PC1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_0
#define RSSI_ADC_PIN PC4
#define RSSI_ADC_CHANNEL ADC_Channel_4
#define EXTERNAL1_ADC_GPIO_PIN PC5
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
// LED strip configuration using RC5 pin.
//#define LED_STRIP
//#define LED_STRIP_TIMER TIM8
//#define USE_LED_STRIP_ON_DMA1_CHANNEL3
//#define WS2811_GPIO GPIOB
//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
//#define WS2811_GPIO_AF GPIO_AF_3
//#define WS2811_PIN GPIO_Pin_15 // TIM8_CH3
//#define WS2811_PIN_SOURCE GPIO_PinSource15
//#define WS2811_TIMER TIM8
//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM8
//#define WS2811_DMA_CHANNEL DMA1_Channel3
//#define WS2811_IRQ DMA1_Channel3_IRQn
#define BLACKBOX
//#define DISPLAY
#define GPS
//#define GTUNE
#define SERIAL_RX
#define TELEMETRY
#define USE_SERVOS
#define USE_CLI
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN PA3
// alternative defaults for AlienFlight F4 target
#define ALIENFLIGHT
// Hardware bind plug at PB2 (Pin 28)
#define HARDWARE_BIND_PLUG
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN PB2
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_QUATERNION
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_TIM5 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8)

View File

@ -0,0 +1,61 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 0, Mode_IPD, GPIO_PinSource7, GPIO_AF_TIM8 }, // PPM IN
{ TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_TIM5 }, // S1_OUT
{ TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_TIM5 }, // S2_OUT
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_TIM2 }, // S3_OUT
{ TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_TIM9 }, // S4_OUT
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_TIM3 }, // S5_OUT
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_TIM3 }, // S6_OUT
};

View File

@ -0,0 +1,161 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "BJF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_NONE
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_RX_SERIAL_PORT 3
#define USBD_PRODUCT_STRING "BlueJayF4"
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_EXTI
#define INVERTER PB15
#define INVERTER_USART USART6
#define BEEPER PB7
#define BEEPER_INVERTED
#define LED0 PB6
#define LED1 PB5
#define LED2 PB4
#define MPU6500_CS_PIN PC4
#define MPU6500_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW180_DEG
//#define MAG
//#define USE_MAG_AK8963
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
//#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PA15
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
//#define M25P16_CS_PIN PB3
//#define M25P16_SPI_INSTANCE SPI3
//#define USE_FLASHFS
//#define USE_FLASH_M25P16
#define USABLE_TIMER_CHANNEL_COUNT 7
// MPU6500 interrupt
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define MPU_INT_EXTI PC5
#define USE_VCP
//#define VBUS_SENSING_PIN PA8
//#define VBUS_SENSING_ENABLED
#define USE_USART1
#define USART1_RX_PIN PA10
#define USART1_TX_PIN PA9
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_USART3
#define USART3_RX_PIN PB11
#define USART3_TX_PIN PB10
#define USE_USART6
#define USART6_RX_PIN PC7
#define USART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 4
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PC4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_I2C_PULLUP
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define VBAT_ADC_CHANNEL ADC_Channel_13
#define GPS
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
#define USE_QUAD_MIXER_ONLY
#define USE_CLI
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_QUATERNION
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM5 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)

View File

@ -0,0 +1,55 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8}, // PPM_IN
{ TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM9}, // S1_OUT
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM3}, // S2_OUT
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM3}, // S3_OUT
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource2, GPIO_AF_TIM2}, // S4_OUT
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5}, // LED Strip
};

View File

@ -0,0 +1,160 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "REVO" //Call it a revo for now so it connects to RFC for testing.
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_MSP_PORT 2
#define CONFIG_RX_SERIAL_PORT 1
#define USBD_PRODUCT_STRING "KopterKontrolNG"
#define LED0 PB5
#define LED1 PB4
#define BEEPER PA8
#define BEEPER_INVERTED
#define INVERTER PC0 // PC0 used as inverter select GPIO
#define INVERTER_USART USART1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
//#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_DETECT_EXTI_LINE EXTI_Line2
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD
#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PB3
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
#define USABLE_TIMER_CHANNEL_COUNT 5 // chane to 6
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_ENABLED
#define USE_USART1
#define USART1_RX_PIN PA10
#define USART1_TX_PIN PA9
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_USART3
#define USART3_RX_PIN PB11
#define USART3_TX_PIN PB10
#define USE_USART6
#define USART6_RX_PIN PC7
#define USART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6-SCL, PB7-SDA
#define USE_I2C_PULLUP
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC1
#define VBAT_ADC_CHANNEL ADC_Channel_11
#define RSSI_ADC_GPIO_PIN PC2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define CURRENT_METER_ADC_PIN PC3
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_13
#define GPS
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
//#define GTUNE
#define USE_QUAD_MIXER_ONLY
#define USE_CLI
#define USE_QUATERNION
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)

View File

@ -0,0 +1,89 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
0xFFFF
};
const uint16_t airPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM1 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, GPIOB, Pin_14, TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM12}, // PPM (5th pin on FlexiIO port)
{ TIM12, GPIOB, Pin_15, TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource15, GPIO_AF_TIM12}, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource6, GPIO_AF_TIM8}, // S3_IN
{ TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource7, GPIO_AF_TIM8}, // S4_IN
{ TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM8}, // S5_IN
{ TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8}, // S6_IN
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM3}, // S1_OUT
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM3}, // S2_OUT
{ TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM9}, // S3_OUT
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource2, GPIO_AF_TIM2}, // S4_OUT
{ TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM5}, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5}, // S6_OUT
};

View File

@ -0,0 +1,144 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "REVO"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
#define CONFIG_FEATURE_RX_SERIAL
#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_MSP_PORT 2
#define CONFIG_RX_SERIAL_PORT 1
#define USBD_PRODUCT_STRING "Revolution"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif
#define LED0 PB5
#define LED1 PB4
#define BEEPER PB4
#define INVERTER PC0 // PC0 used as inverter select GPIO
#define INVERTER_USART USART1
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG
//#define USE_MAG_NAZA
//#define MAG_NAZA_ALIGN CW180_DEG_FLIP
#define BARO
#define USE_BARO_MS5611
//#define PITOT
//#define USE_PITOT_MS4525
//#define MS4525_BUS I2C_DEVICE_EXT
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define USE_USART1
#define USART1_RX_PIN PA10
#define USART1_TX_PIN PA9
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_USART3
#define USART3_RX_PIN PB11
#define USART3_TX_PIN PB10
#define USE_USART6
#define USART6_RX_PIN PC7
#define USART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_ADC
#define CURRENT_METER_ADC_PIN PC1
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_11
#define VBAT_ADC_PIN PC2
#define VBAT_ADC_CHANNEL ADC_Channel_12
#define RSSI_ADC_GPIO_PIN PA0
#define RSSI_ADC_CHANNEL ADC_Channel_0
#define SENSORS_SET (SENSOR_ACC)
//#define LED_STRIP
//#define LED_STRIP_TIMER TIM5
#define GPS
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
//#define GTUNE
#define USE_SERVOS
#define USE_CLI
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_QUATERNION
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM5 | RCC_APB1Periph_TIM12 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)