mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
STM32F4: Drivers
This commit is contained in:
parent
96757c18a2
commit
7ca39bbde6
29 changed files with 2082 additions and 282 deletions
166
src/main/drivers/system_stm32f4xx.c
Normal file
166
src/main/drivers/system_stm32f4xx.c
Normal file
|
@ -0,0 +1,166 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
|
||||
#include "exti.h"
|
||||
#include "debug.h"
|
||||
#include "sensor.h"
|
||||
#include "accgyro.h"
|
||||
#include "accgyro_mpu.h"
|
||||
#include "accgyro_spi_mpu6000.h"
|
||||
#include "accgyro_mpu6500.h"
|
||||
#include "accgyro_spi_mpu9250.h"
|
||||
|
||||
|
||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
if (mpuConfiguration.reset)
|
||||
mpuConfiguration.reset();
|
||||
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void systemResetToBootloader(void)
|
||||
{
|
||||
if (mpuConfiguration.reset)
|
||||
mpuConfiguration.reset();
|
||||
|
||||
*((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX
|
||||
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void enableGPIOPowerUsageAndNoiseReductions(void)
|
||||
{
|
||||
|
||||
RCC_AHB1PeriphClockCmd(
|
||||
RCC_AHB1Periph_GPIOA |
|
||||
RCC_AHB1Periph_GPIOB |
|
||||
RCC_AHB1Periph_GPIOC |
|
||||
RCC_AHB1Periph_GPIOD |
|
||||
RCC_AHB1Periph_GPIOE |
|
||||
#ifdef STM32F40_41xxx
|
||||
RCC_AHB1Periph_GPIOF |
|
||||
RCC_AHB1Periph_GPIOG |
|
||||
RCC_AHB1Periph_GPIOH |
|
||||
RCC_AHB1Periph_GPIOI |
|
||||
#endif
|
||||
RCC_AHB1Periph_CRC |
|
||||
RCC_AHB1Periph_FLITF |
|
||||
RCC_AHB1Periph_SRAM1 |
|
||||
RCC_AHB1Periph_SRAM2 |
|
||||
RCC_AHB1Periph_BKPSRAM |
|
||||
RCC_AHB1Periph_DMA1 |
|
||||
RCC_AHB1Periph_DMA2 |
|
||||
0, ENABLE
|
||||
);
|
||||
|
||||
RCC_AHB2PeriphClockCmd(
|
||||
0, ENABLE);
|
||||
#ifdef STM32F40_41xxx
|
||||
RCC_AHB3PeriphClockCmd(
|
||||
0, ENABLE);
|
||||
#endif
|
||||
RCC_APB1PeriphClockCmd(
|
||||
RCC_APB1Periph_TIM2 |
|
||||
RCC_APB1Periph_TIM3 |
|
||||
RCC_APB1Periph_TIM4 |
|
||||
RCC_APB1Periph_TIM5 |
|
||||
RCC_APB1Periph_TIM6 |
|
||||
RCC_APB1Periph_TIM7 |
|
||||
RCC_APB1Periph_TIM12 |
|
||||
RCC_APB1Periph_TIM13 |
|
||||
RCC_APB1Periph_TIM14 |
|
||||
RCC_APB1Periph_WWDG |
|
||||
RCC_APB1Periph_SPI2 |
|
||||
RCC_APB1Periph_SPI3 |
|
||||
RCC_APB1Periph_USART2 |
|
||||
RCC_APB1Periph_USART3 |
|
||||
RCC_APB1Periph_UART4 |
|
||||
RCC_APB1Periph_UART5 |
|
||||
RCC_APB1Periph_I2C1 |
|
||||
RCC_APB1Periph_I2C2 |
|
||||
RCC_APB1Periph_I2C3 |
|
||||
RCC_APB1Periph_CAN1 |
|
||||
RCC_APB1Periph_CAN2 |
|
||||
RCC_APB1Periph_PWR |
|
||||
RCC_APB1Periph_DAC |
|
||||
0, ENABLE);
|
||||
|
||||
RCC_APB2PeriphClockCmd(
|
||||
RCC_APB2Periph_TIM1 |
|
||||
RCC_APB2Periph_TIM8 |
|
||||
RCC_APB2Periph_USART1 |
|
||||
RCC_APB2Periph_USART6 |
|
||||
RCC_APB2Periph_ADC |
|
||||
RCC_APB2Periph_ADC1 |
|
||||
RCC_APB2Periph_ADC2 |
|
||||
RCC_APB2Periph_ADC3 |
|
||||
RCC_APB2Periph_SDIO |
|
||||
RCC_APB2Periph_SPI1 |
|
||||
RCC_APB2Periph_SYSCFG |
|
||||
RCC_APB2Periph_TIM9 |
|
||||
RCC_APB2Periph_TIM10 |
|
||||
RCC_APB2Periph_TIM11 |
|
||||
0, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOD, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOE, &GPIO_InitStructure);
|
||||
|
||||
#ifdef STM32F40_41xxx
|
||||
GPIO_Init(GPIOF, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOG, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOH, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOI, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
bool isMPUSoftReset(void)
|
||||
{
|
||||
if (RCC->CSR & RCC_CSR_SFTRSTF)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue