Michael Jakob
10 years ago
committed by
Dominic Clifton
11 changed files with 625 additions and 13 deletions
-
1.travis.yml
-
8Makefile
-
10docs/Board - AlienWii32.md
-
4docs/Spektrum bind.md
-
15src/main/config/config.c
-
2src/main/drivers/pwm_mapping.c
-
2src/main/drivers/timer.c
-
372src/main/target/ALIENWIIF3/system_stm32f30x.c
-
76src/main/target/ALIENWIIF3/system_stm32f30x.h
-
144src/main/target/ALIENWIIF3/target.h
-
4src/main/target/NAZE/target.h
@ -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>© 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****/ |
|||
|
@ -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>© 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****/ |
@ -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 "AWF3" // AlienWii32 F3. |
|||
|
|||
#define LED0_GPIO GPIOB |
|||
#define LED0_PIN Pin_4 // Blue LEDs - PB4 |
|||
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB |
|||
#define LED1_GPIO GPIOB |
|||
#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 |
|||
|
|||
#define GYRO_MPU6050_ALIGN CW270_DEG |
|||
|
|||
#define ACC |
|||
#define USE_ACC_MPU6050 |
|||
|
|||
#define ACC_MPU6050_ALIGN CW270_DEG |
|||
|
|||
//#define BARO |
|||
//#define USE_BARO_MS5611 |
|||
|
|||
#define MAG |
|||
#define USE_MAG_AK8975 |
|||
|
|||
#define MAG_AK8975_ALIGN CW0_DEG_FLIP |
|||
|
|||
#define LED0 |
|||
#define LED1 |
|||
|
|||
#define USE_VCP |
|||
#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7) |
|||
#define USE_USART2 // Input - RX (PA3) |
|||
#define USE_USART3 // Servo out - 10/RX (PB11) 11/TX (PB10) |
|||
#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_2 // PA2 - Clashes with PWM6 input. |
|||
#define UART2_RX_PIN GPIO_Pin_3 // PA3 |
|||
#define UART2_GPIO GPIOA |
|||
#define UART2_GPIO_AF GPIO_AF_7 |
|||
#define UART2_TX_PINSOURCE GPIO_PinSource2 |
|||
#define UART2_RX_PINSOURCE GPIO_PinSource3 |
|||
|
|||
// Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP? |
|||
|
|||
#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 SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG) |
|||
|
|||
#define BLACKBOX |
|||
#define SERIAL_RX |
|||
#define GPS |
|||
#define DISPLAY |
|||
|
|||
#define LED_STRIP |
|||
#if 1 |
|||
// LED strip configuration using PWM motor output pin 5. |
|||
#define LED_STRIP_TIMER TIM16 |
|||
|
|||
#define USE_LED_STRIP_ON_DMA1_CHANNEL3 |
|||
#define WS2811_GPIO GPIOA |
|||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA |
|||
#define WS2811_GPIO_AF GPIO_AF_1 |
|||
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1 |
|||
#define WS2811_PIN_SOURCE GPIO_PinSource6 |
|||
#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, PA3 |
|||
#define BIND_PORT GPIOA |
|||
#define BIND_PIN Pin_3 |
|||
|
|||
// Hardware bind plug at PB12 (Pin 25) |
|||
#define BINDPLUG_PORT GPIOB |
|||
#define BINDPLUG_PIN Pin_12 |
|||
|
|||
// alternative defaults for AlienWii32 F3 target |
|||
#define ALIENWII32 |
|||
#define BRUSHED_MOTORS |
|||
#define HARDWARE_BIND_PLUG |
Write
Preview
Loading…
Cancel
Save
Reference in new issue