Disable ADC initialisation on CJMCU. Replace MASSIVEF3 with SPRACINGF3.
Conditional VCP code inclusion. Other minor F1/F3 cleanups.
This commit is contained in:
parent
f825f15a9f
commit
650389afb6
86
Makefile
86
Makefile
|
@ -35,7 +35,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
|
|||
|
||||
FORKNAME = cleanflight
|
||||
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 PORT103R SPARKY ALIENWIIF1
|
||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1
|
||||
|
||||
# Valid targets for OP BootLoader support
|
||||
OPBL_VALID_TARGETS = CC3D
|
||||
|
@ -54,7 +54,7 @@ LINKER_DIR = $(ROOT)/src/main/target
|
|||
# Search path for sources
|
||||
VPATH := $(SRC_DIR):$(SRC_DIR)/startup
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO MASSIVEF3 SPARKY))
|
||||
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY))
|
||||
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
|
||||
USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
|
||||
|
@ -67,21 +67,31 @@ EXCLUDES = stm32f30x_crc.c \
|
|||
|
||||
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
|
||||
|
||||
DEVICE_STDPERIPH_SRC = $(USBPERIPH_SRC) \
|
||||
DEVICE_STDPERIPH_SRC = \
|
||||
$(STDPERIPH_SRC)
|
||||
|
||||
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x:$(USBFS_DIR)/src
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
|
||||
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
|
||||
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(USBFS_DIR)/inc \
|
||||
$(CMSIS_DIR)/CM1/CoreSupport \
|
||||
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x \
|
||||
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
|
||||
|
||||
ifneq ($(TARGET),SPRACINGF3)
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(USBFS_DIR)/inc \
|
||||
$(ROOT)/src/main/vcp
|
||||
|
||||
VPATH := $(VPATH):$(USBFS_DIR)/src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
|
||||
$(USBPERIPH_SRC)
|
||||
|
||||
endif
|
||||
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_256k.ld
|
||||
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
|
@ -92,12 +102,6 @@ ifeq ($(TARGET),CHEBUZZF3)
|
|||
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),MASSIVEF3)
|
||||
# MASSIVEF3 is a VARIANT of STM32F3DISCOVERY
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
||||
endif
|
||||
|
||||
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R))
|
||||
|
||||
|
||||
|
@ -350,7 +354,8 @@ $(error OPBL specified with a unsupported target)
|
|||
endif
|
||||
endif
|
||||
|
||||
CJMCU_SRC = startup_stm32f10x_md_gcc.S \
|
||||
CJMCU_SRC = \
|
||||
startup_stm32f10x_md_gcc.S \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f10x.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
|
@ -371,7 +376,8 @@ CJMCU_SRC = startup_stm32f10x_md_gcc.S \
|
|||
hardware_revision.c \
|
||||
$(COMMON_SRC)
|
||||
|
||||
CC3D_SRC = startup_stm32f10x_md_gcc.S \
|
||||
CC3D_SRC = \
|
||||
startup_stm32f10x_md_gcc.S \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f10x.c \
|
||||
|
@ -394,7 +400,8 @@ CC3D_SRC = startup_stm32f10x_md_gcc.S \
|
|||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
|
||||
STM32F30x_COMMON_SRC = \
|
||||
startup_stm32f30x_md_gcc.S \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f30x.c \
|
||||
drivers/bus_i2c_stm32f30x.c \
|
||||
|
@ -408,29 +415,36 @@ STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
|
|||
drivers/pwm_rx.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f30x.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
drivers/sound_beeper_stm32f30x.c \
|
||||
drivers/system_stm32f30x.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_stm32f30x.c \
|
||||
drivers/timer_stm32f30x.c
|
||||
|
||||
VCP_SRC = \
|
||||
vcp/hw_config.c \
|
||||
vcp/stm32_it.c \
|
||||
vcp/usb_desc.c \
|
||||
vcp/usb_endp.c \
|
||||
vcp/usb_istr.c \
|
||||
vcp/usb_prop.c \
|
||||
vcp/usb_pwr.c
|
||||
vcp/usb_pwr.c \
|
||||
drivers/serial_usb_vcp.c
|
||||
|
||||
NAZE32PRO_SRC = $(STM32F30x_COMMON_SRC) \
|
||||
NAZE32PRO_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
STM32F3DISCOVERY_COMMON_SRC = $(STM32F30x_COMMON_SRC) \
|
||||
STM32F3DISCOVERY_COMMON_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_l3gd20.c \
|
||||
drivers/accgyro_l3gd20.c \
|
||||
drivers/accgyro_lsm303dlhc.c
|
||||
drivers/accgyro_lsm303dlhc.c \
|
||||
$(VCP_SRC)
|
||||
|
||||
STM32F3DISCOVERY_SRC = $(STM32F3DISCOVERY_COMMON_SRC) \
|
||||
STM32F3DISCOVERY_SRC = \
|
||||
$(STM32F3DISCOVERY_COMMON_SRC) \
|
||||
drivers/accgyro_adxl345.c \
|
||||
drivers/accgyro_bma280.c \
|
||||
drivers/accgyro_mma845x.c \
|
||||
|
@ -442,25 +456,33 @@ STM32F3DISCOVERY_SRC = $(STM32F3DISCOVERY_COMMON_SRC) \
|
|||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
CHEBUZZF3_SRC = $(STM32F3DISCOVERY_SRC) \
|
||||
CHEBUZZF3_SRC = \
|
||||
$(STM32F3DISCOVERY_SRC) \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
MASSIVEF3_SRC = $(STM32F3DISCOVERY_SRC) \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
SPARKY_SRC = $(STM32F30x_COMMON_SRC) \
|
||||
SPARKY_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
||||
SPRACINGF3_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC)
|
||||
|
||||
ifeq ($(TARGET),MASSIVEF3)
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_128k.ld
|
||||
endif
|
||||
#ifeq ($(TARGET),SPRACINGF3)
|
||||
#LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_128k.ld
|
||||
#endif
|
||||
|
||||
# Search path and source files for the ST stdperiph library
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
||||
|
|
|
@ -178,9 +178,17 @@ static const mpu6050Config_t *mpu6050Config = NULL;
|
|||
void mpu6050GpioInit(void) {
|
||||
gpio_config_t gpio;
|
||||
|
||||
if (mpu6050Config->gpioAPB2Peripherals) {
|
||||
RCC_APB2PeriphClockCmd(mpu6050Config->gpioAPB2Peripherals, ENABLE);
|
||||
}
|
||||
#ifdef STM32F303
|
||||
if (mpu6050Config->gpioAHBPeripherals) {
|
||||
RCC_AHBPeriphClockCmd(mpu6050Config->gpioAHBPeripherals, ENABLE);
|
||||
}
|
||||
#endif
|
||||
#ifdef STM32F10X
|
||||
if (mpu6050Config->gpioAPB2Peripherals) {
|
||||
RCC_APB2PeriphClockCmd(mpu6050Config->gpioAPB2Peripherals, ENABLE);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
gpio.pin = mpu6050Config->gpioPin;
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
|
|
@ -18,7 +18,12 @@
|
|||
#pragma once
|
||||
|
||||
typedef struct mpu6050Config_s {
|
||||
#ifdef STM32F303
|
||||
uint32_t gpioAHBPeripherals;
|
||||
#endif
|
||||
#ifdef STM32F10X
|
||||
uint32_t gpioAPB2Peripherals;
|
||||
#endif
|
||||
uint16_t gpioPin;
|
||||
GPIO_TypeDef *gpioPort;
|
||||
} mpu6050Config_t;
|
||||
|
|
|
@ -142,10 +142,16 @@ void hmc5883lInit(void)
|
|||
gpio_config_t gpio;
|
||||
|
||||
if (hmc5883Config) {
|
||||
#ifdef STM32F303
|
||||
if (hmc5883Config->gpioAHBPeripherals) {
|
||||
RCC_AHBPeriphClockCmd(hmc5883Config->gpioAHBPeripherals, ENABLE);
|
||||
}
|
||||
#endif
|
||||
#ifdef STM32F10X
|
||||
if (hmc5883Config->gpioAPB2Peripherals) {
|
||||
RCC_APB2PeriphClockCmd(hmc5883Config->gpioAPB2Peripherals, ENABLE);
|
||||
}
|
||||
|
||||
#endif
|
||||
gpio.pin = hmc5883Config->gpioPin;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
|
|
|
@ -18,7 +18,12 @@
|
|||
#pragma once
|
||||
|
||||
typedef struct hmc5883Config_s {
|
||||
#ifdef STM32F303
|
||||
uint32_t gpioAHBPeripherals;
|
||||
#endif
|
||||
#ifdef STM32F10X
|
||||
uint32_t gpioAPB2Peripherals;
|
||||
#endif
|
||||
uint16_t gpioPin;
|
||||
GPIO_TypeDef *gpioPort;
|
||||
} hmc5883Config_t;
|
||||
|
|
|
@ -69,7 +69,7 @@ enum {
|
|||
MAP_TO_SERVO_OUTPUT,
|
||||
};
|
||||
|
||||
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(MASSIVEF3) || defined(PORT103R)
|
||||
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(PORT103R)
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
|
@ -267,15 +267,64 @@ static const uint16_t multiPWM[] = {
|
|||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPWM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef SPRACINGF3
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
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),
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM16 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
static const uint16_t airPWM[] = {
|
||||
// TODO
|
||||
0xFFFF
|
||||
};
|
||||
#endif
|
||||
|
||||
static const uint16_t * const hardwareMaps[] = {
|
||||
multiPWM,
|
||||
multiPPM,
|
||||
|
@ -387,6 +436,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(SPRACINGF3)
|
||||
// remap PWM15+16 as servos
|
||||
if ((timerIndex == PWM15 || timerIndex == PWM16) && timerHardwarePtr->tim == TIM15)
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
#endif
|
||||
|
||||
#if defined(NAZE32PRO) || (defined(STM32F3DISCOVERY) && !defined(CHEBUZZF3))
|
||||
// remap PWM 5+6 or 9+10 as servos - softserial pin pairs require timer ports that use the same timer
|
||||
if (init->useSoftSerial) {
|
||||
|
|
|
@ -65,7 +65,7 @@ typedef struct pwmOutputConfiguration_s {
|
|||
uint8_t motorCount;
|
||||
} pwmOutputConfiguration_t;
|
||||
|
||||
// This indexes into the read-only hardware definition structure, timerHardware_t, as well as into pwmPorts structure with dynamic data.
|
||||
// This indexes into the read-only hardware definition structure, timerHardware_t
|
||||
enum {
|
||||
PWM1 = 0,
|
||||
PWM2,
|
||||
|
@ -80,5 +80,7 @@ enum {
|
|||
PWM11,
|
||||
PWM12,
|
||||
PWM13,
|
||||
PWM14
|
||||
PWM14,
|
||||
PWM15,
|
||||
PWM16
|
||||
};
|
||||
|
|
|
@ -220,6 +220,37 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH3 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH4 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2}, // RC_CH5 - PB4 - *TIM3_CH2
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // RC_CH6 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // RC_CH7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
|
||||
{ TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
|
||||
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10}, // PWM3 - PA11
|
||||
{ TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10}, // PWM4 - PA12
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM5 - PB8
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM6 - PB9
|
||||
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM7 - PA2
|
||||
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM8 - PA3
|
||||
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP
|
||||
};
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||
|
||||
#endif
|
||||
|
||||
#define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
|
||||
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
||||
|
||||
|
|
|
@ -17,18 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef SPARKY
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
#endif
|
||||
|
||||
#ifdef CHEBUZZF3
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 18
|
||||
#endif
|
||||
|
||||
#ifdef CC3D
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
#endif
|
||||
|
||||
#if !defined(USABLE_TIMER_CHANNEL_COUNT)
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#endif
|
||||
|
|
|
@ -73,7 +73,9 @@ static serialPort_t *serialPorts[SERIAL_PORT_COUNT];
|
|||
|
||||
#ifdef STM32F303xC
|
||||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
{SERIAL_PORT_USB_VCP, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
#endif
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
#if (SERIAL_PORT_COUNT > 3)
|
||||
|
@ -85,7 +87,9 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
|||
};
|
||||
|
||||
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
||||
#endif
|
||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||
#if (SERIAL_PORT_COUNT > 3)
|
||||
|
|
|
@ -216,7 +216,7 @@ void init(void)
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if !defined(SPARKY)
|
||||
#ifdef USE_ADC
|
||||
drv_adc_config_t adc_params;
|
||||
|
||||
adc_params.enableRSSI = feature(FEATURE_RSSI_ADC);
|
||||
|
|
|
@ -94,6 +94,15 @@ const mpu6050Config_t *selectMPU6050Config(void)
|
|||
return &nazeRev5MPU6050Config;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3
|
||||
static const mpu6050Config_t spRacingF3MPU6050Config = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
|
||||
.gpioPort = GPIOC,
|
||||
.gpioPin = Pin_13
|
||||
};
|
||||
return &spRacingF3MPU6050Config;
|
||||
#endif
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
@ -406,6 +415,17 @@ static void detectMag(uint8_t magHardwareToUse)
|
|||
|
||||
hmc5883Config = &nazeHmc5883Config;
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3
|
||||
hmc5883Config_t spRacingF3Hmc5883Config = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
|
||||
.gpioPin = Pin_14,
|
||||
.gpioPort = GPIOC
|
||||
};
|
||||
|
||||
hmc5883Config = &spRacingF3Hmc5883Config;
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
retry:
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#define MPU6000_CS_PIN GPIO_Pin_4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
|
||||
|
@ -71,6 +73,8 @@
|
|||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 18
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_L3GD20
|
||||
#define USE_GYRO_MPU6050
|
||||
|
@ -65,6 +67,8 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
|
|
|
@ -98,6 +98,8 @@
|
|||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
|
|
|
@ -1,63 +0,0 @@
|
|||
/*
|
||||
* 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 "MF3A"
|
||||
|
||||
#define LED0_GPIO GPIOE
|
||||
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define LED0_INVERTED
|
||||
#define LED1_GPIO GPIOE
|
||||
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define LED1_INVERTED
|
||||
|
||||
#define BEEP_GPIO GPIOE
|
||||
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define GYRO
|
||||
#define ACC
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
|
@ -117,6 +117,7 @@
|
|||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
|
|
|
@ -85,6 +85,8 @@
|
|||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
|
|
|
@ -95,6 +95,8 @@
|
|||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define LED0
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
#define LED1_PIN Pin_5 // Green LEDs - PB5
|
||||
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
|
|
|
@ -55,9 +55,9 @@
|
|||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 12000000
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*----------------------------------------------------------------------------
|
||||
* PLLMUL | 6
|
||||
* PLLMUL | 9
|
||||
*-----------------------------------------------------------------------------
|
||||
* PREDIV | 1
|
||||
*-----------------------------------------------------------------------------
|
|
@ -0,0 +1,86 @@
|
|||
/*
|
||||
* 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 "SRF3"
|
||||
|
||||
#define LED0_GPIO GPIOB
|
||||
#define LED0_PIN Pin_3
|
||||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
|
||||
#define BEEP_GPIO GPIOC
|
||||
#define BEEP_PIN Pin_15
|
||||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6050
|
||||
|
||||
#define BARO
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
|
||||
#define UART2_RX_PIN GPIO_Pin_15 // PA15
|
||||
#define UART2_GPIO GPIOA
|
||||
#define UART2_GPIO_AF GPIO_AF_7
|
||||
#define UART2_TX_PINSOURCE GPIO_PinSource14
|
||||
#define UART2_RX_PINSOURCE GPIO_PinSource15
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
//#define USE_SPI
|
||||
//#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_6
|
||||
#define WS2811_PIN GPIO_Pin_8
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
@ -54,6 +54,8 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define BLACKBOX
|
||||
|
|
Loading…
Reference in New Issue