Merge pull request #466 from blckmn/development

Removing some more target / platform specific code out of main.c and …
This commit is contained in:
Martin Budden 2016-06-10 11:07:04 +01:00 committed by GitHub
commit bfa70f4ccd
6 changed files with 127 additions and 90 deletions

View File

@ -35,12 +35,7 @@
#define EXTI_CALLBACK_HANDLER_COUNT 1 #define EXTI_CALLBACK_HANDLER_COUNT 1
#endif #endif
typedef struct extiCallbackHandlerConfig_s { extiCallbackHandlerConfig_t extiHandlerConfigs[EXTI_CALLBACK_HANDLER_COUNT];
IRQn_Type irqn;
extiCallbackHandlerFunc* fn;
} extiCallbackHandlerConfig_t;
static extiCallbackHandlerConfig_t extiHandlerConfigs[EXTI_CALLBACK_HANDLER_COUNT];
void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn) void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
{ {
@ -62,7 +57,7 @@ static volatile uint32_t sysTickUptime = 0;
// cached value of RCC->CSR // cached value of RCC->CSR
uint32_t cachedRccCsrValue; uint32_t cachedRccCsrValue;
static void cycleCounterInit(void) void cycleCounterInit(void)
{ {
RCC_ClocksTypeDef clocks; RCC_ClocksTypeDef clocks;
RCC_GetClocksFreq(&clocks); RCC_GetClocksFreq(&clocks);
@ -97,59 +92,6 @@ uint32_t millis(void)
return sysTickUptime; return sysTickUptime;
} }
void systemInit(void)
{
#ifdef CC3D
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
#endif
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
#ifdef STM32F10X
// Turn on clocks for stuff we use
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
#ifdef STM32F4
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
#endif
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
#ifdef STM32F10X
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
digitalHi(GPIOA, gpio.pin);
gpioInit(GPIOA, &gpio);
// Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
#endif
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}
#if 1 #if 1
void delayMicroseconds(uint32_t us) void delayMicroseconds(uint32_t us)
{ {

View File

@ -41,13 +41,26 @@ void failureMode(failureMode_e mode);
void systemReset(void); void systemReset(void);
void systemResetToBootloader(void); void systemResetToBootloader(void);
bool isMPUSoftReset(void); bool isMPUSoftReset(void);
void cycleCounterInit(void);
void enableGPIOPowerUsageAndNoiseReductions(void); void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz // current crystal frequency - 8 or 12MHz
extern uint32_t hse_value; extern uint32_t hse_value;
typedef void extiCallbackHandlerFunc(void); typedef void extiCallbackHandlerFunc(void);
typedef struct extiCallbackHandlerConfig_s {
IRQn_Type irqn;
extiCallbackHandlerFunc* fn;
} extiCallbackHandlerConfig_t;
#ifndef EXTI_CALLBACK_HANDLER_COUNT
#define EXTI_CALLBACK_HANDLER_COUNT 1
#endif
extern extiCallbackHandlerConfig_t extiHandlerConfigs[EXTI_CALLBACK_HANDLER_COUNT];
void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn); void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn); void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);

View File

@ -15,6 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <string.h>
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h> #include <stdlib.h>
@ -22,10 +23,14 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "gpio.h"
#include "nvic.h"
#include "system.h" #include "system.h"
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
// from system_stm32f10x.c
void SetSysClock(bool overclock);
void systemReset(void) void systemReset(void)
{ {
// Generate system reset // Generate system reset
@ -40,7 +45,6 @@ void systemResetToBootloader(void) {
systemReset(); systemReset();
} }
void enableGPIOPowerUsageAndNoiseReductions(void) void enableGPIOPowerUsageAndNoiseReductions(void)
{ {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC, ENABLE);
@ -61,3 +65,48 @@ bool isMPUSoftReset(void)
else else
return false; return false;
} }
void systemInit(void)
{
SetSysClock(false);
#ifdef CC3D
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
#endif
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
// Turn on clocks for stuff we use
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
gpio_config_t gpio;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
digitalHi(GPIOA, gpio.pin);
gpioInit(GPIOA, &gpio);
// Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}

View File

@ -15,6 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <string.h>
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h> #include <stdlib.h>
@ -22,9 +23,11 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "gpio.h"
#include "nvic.h"
#include "system.h" #include "system.h"
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
void SetSysClock();
void systemReset(void) void systemReset(void)
{ {
@ -76,3 +79,26 @@ bool isMPUSoftReset(void)
else else
return false; return false;
} }
void systemInit(void)
{
// Enable FPU
SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2));
SetSysClock();
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}

View File

@ -15,6 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <string.h>
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h> #include <stdlib.h>
@ -22,6 +23,8 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "gpio.h"
#include "nvic.h"
#include "system.h"
#include "exti.h" #include "exti.h"
@ -35,6 +38,7 @@
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
void SetSysClock(void);
void systemReset(void) void systemReset(void)
{ {
@ -81,11 +85,9 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
0, ENABLE 0, ENABLE
); );
RCC_AHB2PeriphClockCmd( RCC_AHB2PeriphClockCmd(0, ENABLE);
0, ENABLE);
#ifdef STM32F40_41xxx #ifdef STM32F40_41xxx
RCC_AHB3PeriphClockCmd( RCC_AHB3PeriphClockCmd(0, ENABLE);
0, ENABLE);
#endif #endif
RCC_APB1PeriphClockCmd( RCC_APB1PeriphClockCmd(
RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM2 |
@ -165,4 +167,30 @@ bool isMPUSoftReset(void)
return false; return false;
} }
void systemInit(void)
{
SetSysClock();
// Configure NVIC preempt/priority groups
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
extern void *isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
// Init cycle counter
cycleCounterInit();
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
// SysTick
SysTick_Config(SystemCoreClock / 1000);
}

View File

@ -135,13 +135,6 @@ void spektrumBind(rxConfig_t *rxConfig);
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig); const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
void sonarInit(const sonarHardware_t *sonarHardware); void sonarInit(const sonarHardware_t *sonarHardware);
#ifdef STM32F10X
// from system_stm32f10x.c
void SetSysClock(bool overclock);
#else
void SetSysClock(void);
#endif
typedef enum { typedef enum {
SYSTEM_STATE_INITIALISING = 0, SYSTEM_STATE_INITIALISING = 0,
SYSTEM_STATE_CONFIG_LOADED = (1 << 0), SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
@ -167,24 +160,13 @@ void init(void)
systemState |= SYSTEM_STATE_CONFIG_LOADED; systemState |= SYSTEM_STATE_CONFIG_LOADED;
#ifdef STM32F3 systemInit();
// start fpu
SCB->CPACR = (0x3 << (10*2)) | (0x3 << (11*2));
SetSysClock();
#endif
#ifdef STM32F1
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
// Configure the Flash Latency cycles and enable prefetch buffer
SetSysClock(0); // TODO - Remove from config in the future
#endif
#ifdef STM32F4
SetSysClock();
#endif
//i2cSetOverclock(masterConfig.i2c_overclock); //i2cSetOverclock(masterConfig.i2c_overclock);
systemInit(); // initialize IO (needed for all IO operations)
IOInitGlobal();
debugMode = masterConfig.debug_mode; debugMode = masterConfig.debug_mode;
#ifdef USE_HARDWARE_REVISION_DETECTION #ifdef USE_HARDWARE_REVISION_DETECTION
@ -194,9 +176,6 @@ void init(void)
// Latch active features to be used for feature() in the remainder of init(). // Latch active features to be used for feature() in the remainder of init().
latchActiveFeatures(); latchActiveFeatures();
// initialize IO (needed for all IO operations)
IOInitGlobal();
#ifdef ALIENFLIGHTF3 #ifdef ALIENFLIGHTF3
if (hardwareRevision == AFF3_REV_1) { if (hardwareRevision == AFF3_REV_1) {
ledInit(false); ledInit(false);