diff --git a/Makefile b/Makefile index 6c17e574e..d0bbda685 100644 --- a/Makefile +++ b/Makefile @@ -45,19 +45,19 @@ FORKNAME = betaflight CC3D_TARGETS = CC3D CC3D_OPBL NAZE_TARGETS = ALIENFLIGHTF1 AFROMMINI -SDCARD_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 SPRACINGF3MINI AQ32_V2 +SDCARD_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 SPRACINGF3MINI AQ32_V2 FURYF3 SPRACINGF3_TARGETS = RMDO IRCFUSIONF3 SERIAL_USB_TARGETS = SPRACINGF3 IRCFUSIONF3 # Valid targets for STM VCP support -VCP_VALID_TARGETS = KKNGF4 REVO BLUEJAYF4 $(CC3D_TARGETS) +VCP_VALID_TARGETS = KKNGF4 FURYF3 REVO BLUEJAYF4 $(CC3D_TARGETS) 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 +F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3 F4_TARGETS = $(F405_TARGETS) $(F405_TARGETS_16) $(F411_TARGETS) VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) @@ -66,7 +66,7 @@ OPBL_VALID_TARGETS = CC3D_OPBL 64K_TARGETS = CJMCU 128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI -256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +256K_TARGETS = EUSTM32F103RC PORT103R $(F3_TARGETS) 512K_TARGETS = $(F411_TARGETS) 1024K_TARGETS = $(F405_TARGETS) $(F405_TARGETS_16) @@ -877,6 +877,30 @@ SINGULARITY_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) +FURYF3_SRC = \ + $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/display_ug2864hsweg01.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_usb_vcp.c \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + drivers/flash_m25p16.c \ + drivers/sonar_hcsr04.c \ + drivers/serial_softserial.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c \ + io/flashfs.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) + ALIENFLIGHTF4_SRC = \ $(STM32F4xx_COMMON_SRC) \ drivers/accgyro_mpu6500.c \ diff --git a/src/main/config/config.c b/src/main/config/config.c index dce58b283..d488f97da 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -518,7 +518,6 @@ static void resetConf(void) masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125; #endif masterConfig.servo_pwm_rate = 50; - masterConfig.use_unsyncedPwm = false; #ifdef CC3D masterConfig.use_buzzer_p6 = 0; diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index b06553335..01bf4e8f3 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -35,7 +35,6 @@ typedef struct master_t { uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) uint8_t motor_pwm_protocol; // Pwm Protocol - uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop #ifdef USE_SERVOS servoMixer_t customServoMixer[MAX_SERVO_RULES]; diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 0facb7c0e..9e7ae6b21 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -54,19 +54,11 @@ typedef struct drv_pwm_config_s { bool useSerialRx; bool useRSSIADC; bool useCurrentMeterADC; -#ifdef STM32F10X bool useUART2; -#endif -#ifdef STM32F303xC bool useUART3; -#endif -#ifdef STM32F4 - bool useUART2; bool useUART6; -#endif bool useVbat; bool useFastPwm; - bool useUnsyncedPwm; bool useSoftSerial; bool useLEDStrip; #ifdef SONAR diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index d284f7b10..51ac90ad4 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -29,7 +29,9 @@ #ifdef USB_IO +#ifdef USB_DETECT_PIN static IO_t usbDetectPin = IO_NONE; +#endif void usbCableDetectDeinit(void) { diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 2257a9157..2ea0b022f 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -582,13 +582,11 @@ const clivalue_t valueTable[] = { { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, - { "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } }, - { "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } }, - { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } }, #ifdef CC3D { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } }, #endif - { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } }, + { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } }, + { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 0, 32000 } }, { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } }, { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } }, diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 992709a1d..0b7a0d042 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -125,11 +125,8 @@ void setGyroSamplingSpeed(uint16_t looptime) { masterConfig.mag_hardware = 1; masterConfig.pid_process_denom = 2; } else if (looptime < 375) { -#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO) || defined(DOGE) - masterConfig.acc_hardware = 0; -#else + masterConfig.acc_hardware = CONFIG_FASTLOOP_PREFERRED_ACC; masterConfig.acc_hardware = 1; -#endif masterConfig.baro_hardware = 1; masterConfig.mag_hardware = 1; masterConfig.pid_process_denom = 2; diff --git a/src/main/main.c b/src/main/main.c index ce704dfcf..f00e88af3 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -334,12 +334,12 @@ void init(void) } else { featureClear(FEATURE_ONESHOT125); } - - pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); // Configurator feature abused for enabling Fast PWM + + // Configurator feature abused for enabling Fast PWM + pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; - pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm; if (feature(FEATURE_3D)) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) @@ -351,7 +351,7 @@ void init(void) pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params); - syncMotors(pwm_params.useUnsyncedPwm && pwm_params.motorPwmRate != PWM_TYPE_BRUSHED); + syncMotors(pwm_params.motorPwmRate == 0 && pwm_params.motorPwmRate != PWM_TYPE_BRUSHED); mixerUsePWMOutputConfiguration(pwmOutputConfiguration); if (!feature(FEATURE_ONESHOT125)) diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 0660ada31..97f1743fd 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -97,7 +97,9 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon .echoIO = IO_TAG(PB0), }; return &sonarHardware; -#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) + +// TODO - move sonar pin selection to CLI +#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) UNUSED(batteryConfig); static const sonarHardware_t const sonarHardware = { .trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 39a36f074..f52a86ab0 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -20,6 +20,7 @@ #define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3. #define ALIENFLIGHT +#define CONFIG_FASTLOOP_PREFERRED_ACC 0 #define USE_HARDWARE_REVISION_DETECTION #define HW_PIN PB2 diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index d11d8dd14..7a9f379c5 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -21,6 +21,8 @@ #define BST_DEVICE_NAME "COLIBRI RACE" #define BST_DEVICE_NAME_LENGTH 12 +#define CONFIG_FASTLOOP_PREFERRED_ACC 0 + #define LED0 PC15 #define LED1 PC14 #define LED2 PC13 diff --git a/src/main/target/DOGE/system_stm32f30x.c b/src/main/target/DOGE/system_stm32f30x.c deleted file mode 100644 index fca696982..000000000 --- a/src/main/target/DOGE/system_stm32f30x.c +++ /dev/null @@ -1,372 +0,0 @@ -/** - ****************************************************************************** - * @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 - * - *

© COPYRIGHT 2014 STMicroelectronics

- * - * 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****/ - diff --git a/src/main/target/DOGE/system_stm32f30x.h b/src/main/target/DOGE/system_stm32f30x.h deleted file mode 100644 index 4f999d305..000000000 --- a/src/main/target/DOGE/system_stm32f30x.h +++ /dev/null @@ -1,76 +0,0 @@ -/** - ****************************************************************************** - * @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 - * - *

© COPYRIGHT 2014 STMicroelectronics

- * - * 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****/ diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index c2e26d335..fc81cc676 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -19,6 +19,8 @@ #define TARGET_BOARD_IDENTIFIER "DOGE" +#define CONFIG_FASTLOOP_PREFERRED_ACC 0 + // tqfp48 pin 34 #define LED0 PA13 diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c new file mode 100644 index 000000000..d2935e350 --- /dev/null +++ b/src/main/target/FURYF3/target.c @@ -0,0 +1,68 @@ + +#include +#include + +#include +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +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_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 + + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM2 | (MAP_TO_SERVO_OUTPUT << 8), + PWM3 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 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] = { + { TIM2, GPIOB, Pin_3, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1}, // PPM IN + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // SS1 - 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}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM4 - S1 + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM5 - S2 + { TIM17, GPIOB, Pin_5, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_10}, // PWM6 - S3 + { TIM16, GPIOB, Pin_4, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_1}, // PWM7 - S4 + + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO TIMER - LED_STRIP + +}; + + diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h new file mode 100644 index 000000000..90a1a7ced --- /dev/null +++ b/src/main/target/FURYF3/target.h @@ -0,0 +1,209 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "FURY" + +#define MPU_INT_EXTI PC4 +#define USE_EXTI +#define CONFIG_PREFER_ACC_ON + +#define LED0 PC14 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define GYRO +#define ACC + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG // changedkb 270 +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG // changedkb 270 + +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW90_DEG // changedkb 270 + +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW90_DEG // changedkb 270 + +#define BARO +#define USE_BARO_MS5611 +#define USE_BARO_BMP280 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +//#define USE_FLASHFS +//#define USE_FLASH_M25P16 +//#define M25P16_CS_PIN PB12 +//#define M25P16_SPI_INSTANCE SPI2 + +#define USE_SDCARD +#define USE_SDCARD_SPI2 + +#define SDCARD_DETECT_INVERTED + +#define SDCARD_DETECT_PIN PB2 +#define SDCARD_DETECT_EXTI_LINE EXTI_Line2 +#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2 +#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_GPIO SPI2_GPIO +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN + +// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128 +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 + +// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 + +// Performance logging for SD card operations: +// #define AFATFS_USE_INTROSPECTIVE_LOGGING + +#define USABLE_TIMER_CHANNEL_COUNT 8 + +#define USB_IO + +#define USE_VCP +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define USE_SOFTSERIAL1 +#define SERIAL_PORT_COUNT 5 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_14 // PA14 +#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 + +#ifndef UART3_GPIO +#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 +#endif + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 1 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 2 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4) + +#define I2C1_SCL_PIN PB8 +#define I2C1_SDA_PIN PB9 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC1 +#define ADC_DMA_CHANNEL DMA1_Channel1 +#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 + +#define VBAT_ADC_GPIO GPIOA +#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 +#define VBAT_ADC_CHANNEL ADC_Channel_1 + +#define RSSI_ADC_GPIO GPIOA +#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 +#define RSSI_ADC_CHANNEL ADC_Channel_2 + +#define CURRENT_METER_ADC_GPIO GPIOA +#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2 +#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3 + +#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 WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define BLACKBOX +#define DISPLAY +#define GPS +#define SERIAL_RX +#define TELEMETRY +#define USE_SERVOS +#define USE_CLI +#define SONAR + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PIN PB11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTF (BIT(4)) + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | 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_TIM16 | RCC_APB2Periph_TIM17) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 312dfe611..7285d132c 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -20,6 +20,8 @@ #define TARGET_BOARD_IDENTIFIER "LUX" #define BOARD_HAS_VOLTAGE_DIVIDER +#define CONFIG_FASTLOOP_PREFERRED_ACC 0 + #define LED0 PC15 #define LED1 PC14 #define LED2 PC13 diff --git a/src/main/target/MOTOLAB/system_stm32f30x.c b/src/main/target/MOTOLAB/system_stm32f30x.c deleted file mode 100644 index fca696982..000000000 --- a/src/main/target/MOTOLAB/system_stm32f30x.c +++ /dev/null @@ -1,372 +0,0 @@ -/** - ****************************************************************************** - * @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 - * - *

© COPYRIGHT 2014 STMicroelectronics

- * - * 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****/ - diff --git a/src/main/target/MOTOLAB/system_stm32f30x.h b/src/main/target/MOTOLAB/system_stm32f30x.h deleted file mode 100644 index 4f999d305..000000000 --- a/src/main/target/MOTOLAB/system_stm32f30x.h +++ /dev/null @@ -1,76 +0,0 @@ -/** - ****************************************************************************** - * @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 - * - *

© COPYRIGHT 2014 STMicroelectronics

- * - * 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****/ diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 23acc0d0c..ebdc2ea3b 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -20,6 +20,8 @@ #define TARGET_BOARD_IDENTIFIER "MOTO" // MotoLab #define USE_CLI +#define CONFIG_FASTLOOP_PREFERRED_ACC 0 + #define LED0 PB5 // Blue LEDs - PB5 //#define LED1 PB9 // Green LEDs - PB9 diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index e749a0511..7f04d1bf5 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -19,6 +19,8 @@ #define TARGET_BOARD_IDENTIFIER "SPEV" +#define CONFIG_FASTLOOP_PREFERRED_ACC 0 + #define LED0 PB8 #define BEEPER PC15 diff --git a/src/main/target/common.h b/src/main/target/common.h index 9fd90daa5..6373874c1 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -17,6 +17,8 @@ #pragma once +#define CONFIG_FASTLOOP_PREFERRED_ACC 1 + #ifdef STM32F4 #define TASK_GYROPID_DESIRED_PERIOD 125 #define SCHEDULER_DELAY_LIMIT 10