Add MOTOLAB build target and associated source files

This commit is contained in:
Moto Moto 2015-08-15 17:33:52 -05:00
parent c49bd407bf
commit 2e351b0991
9 changed files with 825 additions and 6 deletions

View File

@ -38,7 +38,7 @@ FLASH_SIZE ?=
FORKNAME = cleanflight
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 COLIBRI_RACE
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 COLIBRI_RACE MOTOLAB
# Valid targets for OP BootLoader support
OPBL_VALID_TARGETS = CC3D
@ -49,7 +49,7 @@ ifeq ($(TARGET),$(filter $(TARGET),CJMCU))
FLASH_SIZE = 64
else ifeq ($(TARGET),$(filter $(TARGET),NAZE CC3D ALIENWIIF1 OLIMEXINO))
FLASH_SIZE = 128
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE))
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE MOTOLAB))
FLASH_SIZE = 256
else
$(error FLASH_SIZE not configured for target)
@ -72,7 +72,7 @@ VPATH := $(SRC_DIR):$(SRC_DIR)/startup
USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE))
ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE MOTOLAB))
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
@ -549,6 +549,19 @@ SPRACINGF3_SRC = \
$(HIGHEND_SRC) \
$(COMMON_SRC)
MOTOLAB_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/display_ug2864hsweg01.c \
drivers/accgyro_mpu6050.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
drivers/serial_usb_vcp.c \
drivers/flash_m25p16.c \
io/flashfs.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCP_SRC)
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src

102
docs/Board - MotoLab.md Normal file
View File

@ -0,0 +1,102 @@
# Board - MotoLab
The MOTOLAB build target supports the STM32F3-based boards provided by MotoLab.
At present this includes the TornadoFC and MotoF3. The TornadoFC is described here:
http://www.rcgroups.com/forums/showthread.php?t=2473157
The MotoF3 documentation will be provided when the board is available.
Both boards use the STM32F303 microcontroller and have the following features:
* 256K bytes of flash memory
* Floating point math coprocessor
* Three hardware serial port UARTs
* USB using the built-in USB phy that does not interfere with any hadware UART
* Stable voltage regulation
* High-current buzzer/LED output
* Serial LED interface
* Low-pass filtered VBAT input with 1/10 divider ratio
* 8 short-circuit protected PWM outputs, with 5V buffering on the TornadoFC
* On-board 6S-compatible switching regulator (MotoF3)
* Direct mounting option for a Pololu switching regulator for up to 6S lipo operation (TornadoFC)
# Flashing
The MotoLab boards use the internal DFU USB interface on the STM32F3 microcontroller which is not compatible with the Cleanflight configurator flashing tool.
Instead, on Windows you can use the Impulse Flashing Utility from ImpulseRC, available here:
http://www.warpquad.com/ImpulseFlash.zip
Download and unzip the program. Start the program, plug in the USB on the target board, and drag and drop the intended binary file onto the program icon. The program will put the STM32F3 into bootloader mode automatically and load the binary file to the flash.
For programming on Linux, use the dfu-util program which is installed by default on Ubuntu-based systems. Connect the boot pins on the board and plug in the USB.
Verify that the system identifies the DFU device with this command:
```
dfu-util -l
```
The output should list a "Found DFU" device, something like this:
```
dfu-util 0.5
(C) 2005-2008 by Weston Schmidt, Harald Welte and OpenMoko Inc.
(C) 2010-2011 Tormod Volden (DfuSe support)
This program is Free Software and has ABSOLUTELY NO WARRANTY
dfu-util does currently only support DFU version 1.0
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=1, name="@Option Bytes /0x1FFFF800/01*016 e"
```
Use this command to load the binary file to the flash memory on the board:
```
dfu-util --alt 0 -s 0x08000000 -D <binfile>
```
The output should look something like this:
```
dfu-util 0.5
(C) 2005-2008 by Weston Schmidt, Harald Welte and OpenMoko Inc.
(C) 2010-2011 Tormod Volden (DfuSe support)
This program is Free Software and has ABSOLUTELY NO WARRANTY
dfu-util does currently only support DFU version 1.0
Opening DFU USB device... ID 0483:df11
Run-time device DFU version 011a
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Claiming USB DFU Interface...
Setting Alternate Setting #0 ...
Determining device status: state = dfuDNLOAD-IDLE, status = 0
aborting previous incomplete transfer
Determining device status: state = dfuIDLE, status = 0
dfuIDLE, continuing
DFU mode device DFU version 011a
Device returned transfer size 2048
No valid DFU suffix signature
Warning: File has no DFU suffix
DfuSe interface name: "Internal Flash "
```
A binary file is required for the Impulse flashing Utility and dfu-util. The binary file can be built as follows:
```
make TARGET=MOTOLAB clean
make TARGET=MOTOLAB binary
```
To completely erase the flash, create an all-zero file with this command on linux:
```
dd if=/dev/zero of=zero.bin bs=1 count=262144
```
## Todo
Pinout documentation

View File

@ -361,7 +361,7 @@ static void resetConf(void)
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
featureClearAll();
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE)
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB)
featureSet(FEATURE_RX_PPM);
#endif

View File

@ -323,10 +323,8 @@ static const uint16_t airPWM[] = {
// TODO
0xFFFF
};
#endif
#ifdef SPRACINGF3
static const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
@ -404,6 +402,44 @@ static const uint16_t airPWM[] = {
};
#endif
#if defined(MOTOLAB)
static const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM1 | (MAP_TO_MOTOR_OUTPUT << 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),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
static const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_MOTOR_OUTPUT << 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),
PWM8 | (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,
@ -548,6 +584,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
type = MAP_TO_SERVO_OUTPUT;
}
#endif
#if defined(MOTOLAB)
// remap PWM 7+8 as servos
if (timerIndex == PWM7 || timerIndex == PWM8)
type = MAP_TO_SERVO_OUTPUT;
#endif
}
if (init->useChannelForwarding && !init->airplane) {

View File

@ -278,6 +278,29 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#endif
#if defined(MOTOLAB)
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_1}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17)
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#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

View File

@ -120,6 +120,19 @@ const mpu6050Config_t *selectMPU6050Config(void)
return &spRacingF3MPU6050Config;
#endif
#ifdef MOTOLAB
static const mpu6050Config_t MotolabF3MPU6050Config = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_15,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource15,
.exti_line = EXTI_Line15,
.exti_irqn = EXTI15_10_IRQn
};
return &MotolabF3MPU6050Config;
#endif
return NULL;
}

View File

@ -0,0 +1,372 @@
/**
******************************************************************************
* @file system_stm32f30x.c
* @author MCD Application Team
* @version V1.1.1
* @date 28-March-2014
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
* This file contains the system clock configuration for STM32F30x devices,
* and is generated by the clock configuration tool
* stm32f30x_Clock_Configuration_V1.0.0.xls
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
* and Divider factors, AHB/APBx prescalers and Flash settings),
* depending on the configuration made in the clock xls tool.
* This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f30x.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
* configure the system clock before to branch to main program.
*
* 3. If the system clock source selected by user fails to startup, the SystemInit()
* function will do nothing and HSI still used as system clock source. User can
* add some code to deal with this issue inside the SetSysClock() function.
*
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
* through PLL, and you are using different crystal you have to adapt the HSE
* value to your own configuration.
*
* 5. This file configures the system clock as follows:
*=============================================================================
* Supported STM32F30x device
*-----------------------------------------------------------------------------
* System Clock source | PLL (HSE)
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 72000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 72000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 2
*-----------------------------------------------------------------------------
* APB1 Prescaler | 2
*-----------------------------------------------------------------------------
* HSE Frequency(Hz) | 8000000
*----------------------------------------------------------------------------
* PLLMUL | 9
*-----------------------------------------------------------------------------
* PREDIV | 1
*-----------------------------------------------------------------------------
* USB Clock | ENABLE
*-----------------------------------------------------------------------------
* Flash Latency(WS) | 2
*-----------------------------------------------------------------------------
* Prefetch Buffer | ON
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f30x_system
* @{
*/
/** @addtogroup STM32F30x_System_Private_Includes
* @{
*/
#include "stm32f30x.h"
uint32_t hse_value = HSE_VALUE;
/**
* @}
*/
/* Private typedef -----------------------------------------------------------*/
/** @addtogroup STM32F30x_System_Private_Defines
* @{
*/
/*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
/**
* @}
*/
/* Private macro -------------------------------------------------------------*/
/** @addtogroup STM32F30x_System_Private_Variables
* @{
*/
uint32_t SystemCoreClock = 72000000;
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
/**
* @}
*/
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
* @{
*/
void SetSysClock(void);
/**
* @}
*/
/** @addtogroup STM32F30x_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* Initialize the Embedded Flash Interface, the PLL and update the
* SystemFrequency variable.
* @param None
* @retval None
*/
void SystemInit(void)
{
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
#endif
/* Reset the RCC clock configuration to the default reset state ------------*/
/* Set HSION bit */
RCC->CR |= (uint32_t)0x00000001;
/* Reset CFGR register */
RCC->CFGR &= 0xF87FC00C;
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
/* Reset HSEBYP bit */
RCC->CR &= (uint32_t)0xFFFBFFFF;
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
RCC->CFGR &= (uint32_t)0xFF80FFFF;
/* Reset PREDIV1[3:0] bits */
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
/* Disable all interrupts */
RCC->CIR = 0x00000000;
/* Configure the System clock source, PLL Multiplier and Divider factors,
AHB/APBx prescalers and Flash settings ----------------------------------*/
//SetSysClock(); // called from main()
#ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
#endif
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case 0x00: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case 0x08: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2;
if (pllsource == 0x00)
{
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
}
else
{
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
}
break;
default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ----------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
* AHB/APBx prescalers and Flash settings
* @note This function should be called only once the RCC clock configuration
* is reset to the default reset state (done in SystemInit() function).
* @param None
* @retval None
*/
void SetSysClock(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer and set Flash Latency */
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
/* HCLK = SYSCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK / 2 */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
/* PLL configuration */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,76 @@
/**
******************************************************************************
* @file system_stm32f30x.h
* @author MCD Application Team
* @version V1.1.1
* @date 28-March-2014
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f30x_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F30X_H
#define __SYSTEM_STM32F30X_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/** @addtogroup STM32F30x_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F30X_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,178 @@
/*
* 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 "MOTO" // MotoLab
#define USE_CLI
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_5 // Blue LEDs - PB5
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_9 // Green LEDs - PB9
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_0
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
#define BEEPER_INVERTED
#define BEEPER
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW180_DEG
#define ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW180_DEG
//#define BARO
//#define USE_BARO_MS5611
//#define MAG
//#define USE_MAG_HMC5883
#define LED0
#define USE_VCP
#define USE_USART1
#define USE_USART2
#define USE_USART3
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN GPIO_Pin_6 // PB6
#define UART1_RX_PIN GPIO_Pin_7 // PB7
#define UART1_GPIO GPIOB
#define UART1_GPIO_AF GPIO_AF_7
#define UART1_TX_PINSOURCE GPIO_PinSource6
#define UART1_RX_PINSOURCE GPIO_PinSource7
#define UART2_TX_PIN GPIO_Pin_3 // PB3
#define UART2_RX_PIN GPIO_Pin_4 // PB4
#define UART2_GPIO GPIOB
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource3
#define UART2_RX_PINSOURCE GPIO_PinSource4
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL_GPIO GPIOA
#define I2C2_SCL_GPIO_AF GPIO_AF_4
#define I2C2_SCL_PIN GPIO_Pin_9
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SDA_GPIO GPIOA
#define I2C2_SDA_GPIO_AF GPIO_AF_4
#define I2C2_SDA_PIN GPIO_Pin_10
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define USE_SPI
#define USE_SPI_DEVICE_2
#define M25P16_CS_GPIO GPIOB
#define M25P16_CS_PIN GPIO_Pin_12
#define M25P16_SPI_INSTANCE SPI2
//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define SENSORS_SET (SENSOR_ACC)
#define TELEMETRY
#define BLACKBOX
#define SERIAL_RX
//#define GPS
#define DISPLAY
#define USE_SERVOS
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_5
#define VBAT_ADC_CHANNEL ADC_Channel_2
//#define CURRENT_METER_ADC_GPIO GPIOA
//#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
//#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define LED_STRIP
#if 1
#define LED_STRIP_TIMER TIM16
#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_1
#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#endif
#if 0
// Alternate LED strip pin
// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1
#define LED_STRIP_TIMER TIM17
#define USE_LED_STRIP_ON_DMA1_CHANNEL7
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource7
#define WS2811_TIMER TIM17
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17
#define WS2811_DMA_CHANNEL DMA1_Channel7
#define WS2811_IRQ DMA1_Channel7_IRQn
#endif
//#define SPEKTRUM_BIND
// USART2, PB4
#define BIND_PORT GPIOB
#define BIND_PIN Pin_4