1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

OP-1275 F0 support: fix make scripts, bootloader size, linker scripts, add other missing pios drivers.

This commit is contained in:
Alessio Morale 2014-05-19 01:39:48 +02:00
parent 5ab9806279
commit 4d1e8cf5a7
13 changed files with 239 additions and 112 deletions

View File

@ -25,9 +25,9 @@ EXTRAINCDIRS += $(PIOS_DEVLIB)inc
# CMSIS for the F0
include $(PIOSCOMMON)/libraries/CMSIS/library.mk
CMSIS_DEVICEDIR = $(PIOS_DEVLIB)libraries/CMSIS/Device/ST/STM32F0xx/
CMSIS_DEVICEDIR = $(PIOS_DEVLIB)libraries/CMSIS/Device/ST/STM32F0xx/Source
CMSIS_DIR = $(PIOS_DEVLIB)/libraries/CMSIS/Include
EXTRAINCDIRS += $(CMSIS_DEVICEDIR)/Include
EXTRAINCDIRS += $(CMSIS_DEVICEDIR)/../Include
EXTRAINCDIRS += $(CMSIS_DIR)
# ST Peripheral library
PERIPHLIB = $(PIOS_DEVLIB)libraries/STM32F0xx_StdPeriph_Driver

View File

@ -3,6 +3,8 @@ PROVIDE ( vPortSVCHandler = 0 ) ;
PROVIDE ( xPortPendSVHandler = 0 ) ;
PROVIDE ( xPortSysTickHandler = 0 ) ;
PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO));
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
_irq_stack_size = 0x200;

View File

@ -1,9 +1,8 @@
MEMORY
{
/* rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K */
/* ram (rwx) : ORIGIN = 0x20000000, LENGTH = 4K */
BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2K - 0x80
BD_INFO (r) : ORIGIN = 0x08000000 + 2K - 0x80, LENGTH = 0x80
FLASH (rx) : ORIGIN = 0x08000000 + 2K, LENGTH = 32K - 2K
SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 4K
BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 8K - 0x80
BD_INFO (r) : ORIGIN = 0x08000000 + 8K - 0x80, LENGTH = 0x80
FLASH (rx) : ORIGIN = 0x08000000 + 8K, LENGTH = 32K - 8K
VTRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0xc0 /* First part of RAM is reserved to the vector table */
SRAM (rwx) : ORIGIN = 0x20000000 + 0xc0, LENGTH = 4K - 0xc0
}

View File

@ -44,6 +44,7 @@ SECTIONS
. = ALIGN(4);
_etext = .;
.ram_vector_table(NOLOAD): {*(.ram_vector_table)} >VTRAM
_sidata = .;
/*

View File

@ -32,6 +32,7 @@
#include <pios_bkp.h>
#include <stm32f0xx.h>
#include <stm32f0xx_rtc.h>
#include <stm32f0xx_rcc.h>
#include <stm32f0xx_pwr.h>
/****************************************************************************************
@ -60,10 +61,10 @@ void PIOS_BKP_Init(void)
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);
/* Enable PWR and BKP clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE);
/* Clear Tamper pin Event(TE) pending flag */
BKP_ClearFlag();
RTC_ClearFlag(RTC_FLAG_TAMP1F | RTC_FLAG_TAMP2F);
}
uint16_t PIOS_BKP_ReadRegister(uint32_t regnumber)
@ -71,7 +72,7 @@ uint16_t PIOS_BKP_ReadRegister(uint32_t regnumber)
if (PIOS_BKP_REGISTERS_COUNT < regnumber) {
PIOS_Assert(0);
} else {
return (uint16_t)BKP_ReadBackupRegister(pios_bkp_registers_map[regnumber]);
return (uint16_t)RTC_ReadBackupRegister(pios_bkp_registers_map[regnumber]);
}
}
@ -80,7 +81,7 @@ void PIOS_BKP_WriteRegister(uint32_t regnumber, uint16_t data)
if (PIOS_BKP_REGISTERS_COUNT < regnumber) {
PIOS_Assert(0);
} else {
BKP_WriteBackupRegister(pios_bkp_registers_map[regnumber], (uint32_t)data);
RTC_WriteBackupRegister(pios_bkp_registers_map[regnumber], (uint32_t)data);
}
}

View File

@ -33,7 +33,7 @@
#ifdef PIOS_INCLUDE_BL_HELPER
#include <pios_board_info.h>
#include <stm32f10x_flash.h>
#include <stm32f0xx_flash.h>
#include <stdbool.h>
uint8_t *PIOS_BL_HELPER_FLASH_If_Read(uint32_t SectorAddress)

View File

@ -31,17 +31,12 @@
*/
#include <pios.h>
#include <stm32f0xx_rcc.h>
#include <stm32f0xx_tim.h>
#ifdef PIOS_INCLUDE_DELAY
/* these should be defined by CMSIS, but they aren't */
#define DWT_CTRL (*(volatile uint32_t *)0xe0001000)
#define CYCCNTENA (1 << 0)
#define DWT_CYCCNT (*(volatile uint32_t *)0xe0001004)
/* cycles per microsecond */
static uint32_t us_ticks;
#define DELAY_COUNTER (TIM2->CNT)
/**
* Initialises the Timer used by PIOS_DELAY functions.
@ -51,18 +46,25 @@ static uint32_t us_ticks;
int32_t PIOS_DELAY_Init(void)
{
RCC_ClocksTypeDef clocks;
// unfortunately F0 does not allow access to DWT and CoreDebug functionality from CPU side
// thus we are going to use timer3 for timing measurement
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
/* compute the number of system clocks per microsecond */
RCC_GetClocksFreq(&clocks);
us_ticks = clocks.SYSCLK_Frequency / 1000000;
PIOS_DEBUG_Assert(us_ticks > 1);
/* turn on access to the DWT registers */
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
/* enable the CPU cycle counter */
DWT_CTRL |= CYCCNTENA;
const TIM_TimeBaseInitTypeDef timerInit = {
.TIM_Prescaler = 8,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
// period (1.25 uS per period
.TIM_Period = 0,
.TIM_RepetitionCounter = 0x0000,
};
// Stop timer
TIM_Cmd(TIM2, DISABLE);
// Configure timebase and internal clock
TIM_TimeBaseInit(TIM2, (TIM_TimeBaseInitTypeDef*)&timerInit);
TIM_InternalClockConfig(TIM2);
TIM_SetCounter(TIM2, 0);
TIM_Cmd(TIM2, ENABLE);
return 0;
}
@ -81,10 +83,10 @@ int32_t PIOS_DELAY_Init(void)
int32_t PIOS_DELAY_WaituS(uint32_t uS)
{
uint32_t elapsed = 0;
uint32_t last_count = DWT_CYCCNT;
uint32_t last_count = DELAY_COUNTER;
for (;;) {
uint32_t current_count = DWT_CYCCNT;
uint32_t current_count = DELAY_COUNTER;
uint32_t elapsed_uS;
/* measure the time elapsed since the last time we checked */
@ -92,7 +94,7 @@ int32_t PIOS_DELAY_WaituS(uint32_t uS)
last_count = current_count;
/* convert to microseconds */
elapsed_uS = elapsed / us_ticks;
elapsed_uS = elapsed;
if (elapsed_uS >= uS) {
break;
}
@ -101,7 +103,7 @@ int32_t PIOS_DELAY_WaituS(uint32_t uS)
uS -= elapsed_uS;
/* keep fractional microseconds for the next iteration */
elapsed %= us_ticks;
elapsed = 0;
}
/* No error */
@ -135,7 +137,7 @@ int32_t PIOS_DELAY_WaitmS(uint32_t mS)
*/
uint32_t PIOS_DELAY_GetuS(void)
{
return DWT_CYCCNT / us_ticks;
return DELAY_COUNTER;
}
/**
@ -154,7 +156,7 @@ uint32_t PIOS_DELAY_GetuSSince(uint32_t t)
*/
uint32_t PIOS_DELAY_GetRaw()
{
return DWT_CYCCNT;
return DELAY_COUNTER;
}
/**
@ -163,9 +165,9 @@ uint32_t PIOS_DELAY_GetRaw()
*/
uint32_t PIOS_DELAY_DiffuS(uint32_t raw)
{
uint32_t diff = DWT_CYCCNT - raw;
uint32_t diff = - raw;
return diff / us_ticks;
return diff;
}
#endif /* PIOS_INCLUDE_DELAY */

View File

@ -87,19 +87,18 @@ static uint8_t PIOS_EXTI_line_to_index(uint32_t line)
uint8_t PIOS_EXTI_gpio_port_to_exti_source_port(GPIO_TypeDef *gpio_port)
{
switch ((uint32_t)gpio_port) {
case (uint32_t)GPIOA: return GPIO_PortSourceGPIOA;
case (uint32_t)GPIOA: return EXTI_PortSourceGPIOA;
case (uint32_t)GPIOB: return GPIO_PortSourceGPIOB;
case (uint32_t)GPIOB: return EXTI_PortSourceGPIOB;
case (uint32_t)GPIOC: return GPIO_PortSourceGPIOC;
case (uint32_t)GPIOC: return EXTI_PortSourceGPIOC;
case (uint32_t)GPIOD: return GPIO_PortSourceGPIOD;
case (uint32_t)GPIOD: return EXTI_PortSourceGPIOD;
case (uint32_t)GPIOE: return GPIO_PortSourceGPIOE;
case (uint32_t)GPIOE: return EXTI_PortSourceGPIOE;
case (uint32_t)GPIOF: return GPIO_PortSourceGPIOF;
case (uint32_t)GPIOF: return EXTI_PortSourceGPIOF;
case (uint32_t)GPIOG: return GPIO_PortSourceGPIOG;
}
PIOS_Assert(0);
@ -167,16 +166,16 @@ int32_t PIOS_EXTI_Init(const struct pios_exti_cfg *cfg)
pios_exti_line_to_cfg_map[line_index] = cfg_index;
/* Initialize the GPIO pin */
GPIO_Init(cfg->pin.gpio, &cfg->pin.init);
GPIO_Init(cfg->pin.gpio,(GPIO_InitTypeDef*) &cfg->pin.init);
/* Set up the EXTI interrupt source */
uint8_t exti_source_port = PIOS_EXTI_gpio_port_to_exti_source_port(cfg->pin.gpio);
uint8_t exti_source_pin = PIOS_EXTI_gpio_pin_to_exti_source_pin(cfg->pin.init.GPIO_Pin);
GPIO_EXTILineConfig(exti_source_port, exti_source_pin);
EXTI_Init(&cfg->exti.init);
SYSCFG_EXTILineConfig(exti_source_port, exti_source_pin);
EXTI_Init((EXTI_InitTypeDef*)&cfg->exti.init);
/* Enable the interrupt channel */
NVIC_Init(&cfg->irq.init);
NVIC_Init((NVIC_InitTypeDef*)&cfg->irq.init);
return 0;
@ -200,6 +199,8 @@ static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index)
return cfg->vector();
}
/* Bind Interrupt Handlers */
#ifdef PIOS_INCLUDE_FREERTOS
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
@ -214,14 +215,12 @@ static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index)
}
#endif
/* Bind Interrupt Handlers */
static void PIOS_EXTI_0_irq_handler(void)
{
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(0, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
@ -235,7 +234,7 @@ static void PIOS_EXTI_1_irq_handler(void)
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(1, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
@ -249,7 +248,7 @@ static void PIOS_EXTI_2_irq_handler(void)
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(2, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
@ -263,7 +262,7 @@ static void PIOS_EXTI_3_irq_handler(void)
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(3, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
@ -277,7 +276,7 @@ static void PIOS_EXTI_4_irq_handler(void)
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(4, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
@ -291,7 +290,7 @@ static void PIOS_EXTI_9_5_irq_handler(void)
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(5, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(6, xHigherPriorityTaskWoken);
@ -309,7 +308,7 @@ static void PIOS_EXTI_15_10_irq_handler(void)
#ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(10, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(11, xHigherPriorityTaskWoken);

View File

@ -48,13 +48,22 @@ int32_t PIOS_GPIO_Init(uint32_t *gpios_dev_id, const struct pios_gpio_cfg *cfg)
/* Enable the peripheral clock for the GPIO */
switch ((uint32_t)gpio->pin.gpio) {
case (uint32_t)GPIOA:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
break;
case (uint32_t)GPIOB:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
break;
case (uint32_t)GPIOC:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOC, ENABLE);
break;
case (uint32_t)GPIOD:
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOD, ENABLE);
break;
case (uint32_t)GPIOE:
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOE, ENABLE);
break;
case (uint32_t)GPIOF:
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOF, ENABLE);
break;
default:
PIOS_Assert(0);
@ -62,10 +71,10 @@ int32_t PIOS_GPIO_Init(uint32_t *gpios_dev_id, const struct pios_gpio_cfg *cfg)
}
if (gpio->remap) {
GPIO_PinRemapConfig(gpio->remap, ENABLE);
GPIO_PinAFConfig(gpio->pin.gpio, gpio->pin.init.GPIO_Pin, gpio->remap);
}
GPIO_Init(gpio->pin.gpio, &gpio->pin.init);
GPIO_Init(gpio->pin.gpio, (GPIO_InitTypeDef*)&gpio->pin.init);
PIOS_GPIO_Off(*gpios_dev_id, i);
}

View File

@ -3,11 +3,11 @@
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_PWM PWM Input Functions
* @brief Code to measure with PWM input
* @brief Code to measure with PWM input
* @{
*
* @file pios_pwm.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief PWM Input functions (STM32 dependent)
* @see The GNU Public License (GPL) Version 3
*
@ -49,30 +49,38 @@ static uint8_t rtc_callback_next = 0;
void PIOS_RTC_Init(const struct pios_rtc_cfg *cfg)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_BKP | RCC_APB1Periph_PWR,
ENABLE);
RCC_BackupResetCmd(ENABLE);
RCC_BackupResetCmd(DISABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE);
PWR_BackupAccessCmd(ENABLE);
// Divide external 8 MHz clock to 1 MHz
RCC_RTCCLKConfig(cfg->clksrc);
RCC_RTCCLKCmd(ENABLE);
RTC_WaitForLastTask();
RTC_WaitForSynchro();
RTC_WaitForLastTask();
RTC_WakeUpCmd(DISABLE);
// Divide 1 Mhz clock by 16 -> 62.5 khz
RTC_WakeUpClockConfig(RTC_WakeUpClock_RTCCLK_Div16);
// Divide 62.5 khz by 200 to get 625 Hz
RTC_SetWakeUpCounter(cfg->prescaler); // cfg->prescaler);
RTC_WakeUpCmd(ENABLE);
/* Configure and enable the RTC Second interrupt */
NVIC_Init(&cfg->irq.init);
RTC_ITConfig(RTC_IT_SEC, ENABLE);
RTC_WaitForLastTask();
EXTI_InitTypeDef ExtiInit = {
.EXTI_Line = EXTI_Line22, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
};
EXTI_Init(&ExtiInit);
NVIC_Init((NVIC_InitTypeDef*)&cfg->irq.init);
RTC_ITConfig(RTC_IT_WUT, ENABLE);
RTC_SetPrescaler(cfg->prescaler);
RTC_WaitForLastTask();
RTC_SetCounter(0);
RTC_WaitForLastTask();
RTC_ClearFlag(RTC_FLAG_WUTF);
}
uint32_t PIOS_RTC_Counter()
{
return RTC_GetCounter();
return RTC_GetWakeUpCounter();
}
/* FIXME: This shouldn't use hard-coded clock rates, dividers or prescalers.
@ -106,7 +114,7 @@ bool PIOS_RTC_RegisterTickCallback(void (*fn)(uint32_t id), uint32_t data)
void PIOS_RTC_irq_handler(void)
{
if (RTC_GetITStatus(RTC_IT_SEC)) {
if (RTC_GetITStatus(RTC_IT_WUT)) {
/* Call all registered callbacks */
for (uint8_t i = 0; i < rtc_callback_next; i++) {
struct rtc_callback_entry *cb = &rtc_callback_list[i];
@ -115,10 +123,12 @@ void PIOS_RTC_irq_handler(void)
}
}
/* Wait until last write operation on RTC registers has finished */
RTC_WaitForLastTask();
/* Clear the RTC Second interrupt */
RTC_ClearITPendingBit(RTC_IT_SEC);
RTC_ClearITPendingBit(RTC_IT_WUT);
}
if (EXTI_GetITStatus(EXTI_Line22) != RESET) {
EXTI_ClearITPendingBit(EXTI_Line22);
}
}

View File

@ -7,8 +7,8 @@
* @{
*
* @file pios_sys.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
* @author Michael Smith Copyright (C) 2011
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Sets up basic STM32 system hardware, functions are called from Main.
* @see The GNU Public License (GPL) Version 3
*
@ -33,6 +33,8 @@
#ifdef PIOS_INCLUDE_SYS
__IO uint32_t VectorTable[48] __attribute__((section(".ram_vector_table")));
/* Private Function Prototypes */
void NVIC_Configuration(void);
void SysTick_Handler(void);
@ -49,25 +51,103 @@ void PIOS_SYS_Init(void)
{
/* Setup STM32 system (RCC, clock, PLL and Flash configuration) - CMSIS Function */
SystemInit();
SystemCoreClockUpdate(); /* update SystemCoreClock for use elsewhere */
/*
* @todo might make sense to fetch the bus clocks and save them somewhere to avoid
* having to use the clunky get-all-clocks API everytime we need one.
*/
/* Initialise Basic NVIC */
/* do this early to ensure that we take exceptions in the right place */
NVIC_Configuration();
/* Init the delay system */
PIOS_DELAY_Init();
/* Enable GPIOA, GPIOB, GPIOC, GPIOD, GPIOE and AFIO clocks */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE |
RCC_APB2Periph_AFIO, ENABLE);
/*
* Turn on all the peripheral clocks.
* Micromanaging clocks makes no sense given the power situation in the system, so
* light up everything we might reasonably use here and just leave it on.
*/
RCC_AHBPeriphClockCmd(
RCC_AHBPeriph_GPIOA |
RCC_AHBPeriph_GPIOB |
// RCC_AHBPeriph_GPIOC |
// RCC_AHBPeriph_GPIOD |
// RCC_AHBPeriph_GPIOE |
// RCC_AHBPeriph_GPIOF |
// RCC_AHBPeriph_CRC |
RCC_AHBPeriph_FLITF |
RCC_AHBPeriph_SRAM |
RCC_AHBPeriph_DMA1
, ENABLE);
#if (PIOS_USB_ENABLED)
/* Ensure that pull-up is active on detect pin */
/*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);
/*
* Configure all pins as input / pullup to avoid issues with
* uncommitted pins, excepting special-function pins that we need to
* remain as-is.
*/
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_InitStructure.GPIO_Pin = PIOS_USB_DETECT_GPIO_PIN;
GPIO_Init(PIOS_USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
#endif
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input
/* Initialise Basic NVIC */
NVIC_Configuration();
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14 ); // leave SWD 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);
GPIO_Init(GPIOF, &GPIO_InitStructure);
}
/**
@ -99,8 +179,9 @@ int32_t PIOS_SYS_Reset(void)
PIOS_LED_Off(PIOS_LED_ALARM);
#endif /* PIOS_LED_ALARM */
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
/* XXX F10x port resets most (but not all) peripherals ... do we care? */
/* Reset STM32 */
NVIC_SystemReset();
while (1) {
@ -116,13 +197,13 @@ int32_t PIOS_SYS_Reset(void)
*/
uint32_t PIOS_SYS_getCPUFlashSize(void)
{
return (uint32_t)MEM16(0x1FFFF7E0) * 1000;
return (uint32_t)MEM16(0x1fff7a22) * 1024; // it might be possible to locate in the OTP area, but haven't looked and not documented
}
/**
* Returns the serial number as a string
* param[out] uint8_t pointer to a string which can store at least 12 bytes
* (12 bytes returned for STM32)
* param[out] str pointer to a string which can store at least 32 digits + zero terminator!
* (24 digits returned for STM32)
* return < 0 if feature not supported
*/
int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array)
@ -131,7 +212,7 @@ int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array)
/* Stored in the so called "electronic signature" */
for (i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) {
uint8_t b = MEM8(0x1ffff7e8 + i);
uint8_t b = MEM8(0x1fff7a10 + i);
array[i] = b;
}
@ -152,7 +233,7 @@ int32_t PIOS_SYS_SerialNumberGet(char *str)
/* Stored in the so called "electronic signature" */
for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) {
uint8_t b = MEM8(0x1ffff7e8 + (i / 2));
uint8_t b = MEM8(0x1fff7a10 + (i / 2));
if (!(i & 1)) {
b >>= 4;
}
@ -171,13 +252,20 @@ int32_t PIOS_SYS_SerialNumberGet(char *str)
*/
void NVIC_Configuration(void)
{
/* Set the Vector Table base address as specified in .ld file */
/* Relocate by software the vector table to the internal SRAM at 0x20000000 ***/
extern void *pios_isr_vector_table_base;
NVIC_SetVectorTable((uint32_t)&pios_isr_vector_table_base, 0x0);
/* Copy the vector table from the Flash (mapped at the base of the application
load address 0x08003000) to the base address of the SRAM at 0x20000000. */
for(uint32_t i = 0; i < 48; i++)
{
VectorTable[i] = *(__IO uint32_t*)(pios_isr_vector_table_base + (i<<2));
}
/* 4 bits for Interrupt priorities so no sub priorities */
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
/* Enable the SYSCFG peripheral clock*/
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, ENABLE);
/* Remap SRAM at 0x00000000 */
SYSCFG_MemoryRemapConfig(SYSCFG_MemoryRemap_SRAM);
/* Configure HCLK clock as SysTick clock source. */
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);

View File

@ -796,7 +796,7 @@ void UAVObjInstanceWriteToLog(UAVObjHandle obj_handle, uint16_t instId)
unlock_exit:
xSemaphoreGiveRecursive(mutex);
}
#ifdef PIOS_INCLUDE_FLASH
/**
* Save the data of the specified object to the file system (SD card).
* If the object contains multiple instances, all of them will be saved.
@ -891,7 +891,21 @@ int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId)
PIOS_FLASHFS_ObjDelete(pios_uavo_settings_fs_id, UAVObjGetID(obj_handle), instId);
return 0;
}
#else // PIOS_INCLUDE_FLASH
int32_t UAVObjSave(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId){
return 0;
}
int32_t UAVObjLoad(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId){
return 0;
}
int32_t UAVObjDelete(__attribute__((unused)) UAVObjHandle obj_handle, __attribute__((unused)) uint16_t instId)
{
return 0;
}
#endif // PIOS_INCLUDE_FLASH
/**
* Save all settings objects to the SD card.
* @return 0 if success or -1 if failure

View File

@ -49,6 +49,8 @@ ifeq ($(MCU),cortex-m3)
include $(PIOS)/stm32f10x/library.mk
else ifeq ($(MCU),cortex-m4)
include $(PIOS)/stm32f4xx/library.mk
else ifeq ($(MCU),cortex-m0)
include $(PIOS)/stm32f0x/library.mk
else
$(error Unsupported MCU: $(MCU))
endif
@ -90,12 +92,12 @@ SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
SRC += $(PIOSCOMMON)/pios_sbus.c
SRC += $(PIOSCOMMON)/pios_sdcard.c
SRC += $(PIOSCOMMON)/pios_led.c
ifneq ($(PIOS_OMITS_USB),YES)
## PIOS USB related files
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
SRC += $(PIOSCOMMON)/pios_usb_util.c
endif
## PIOS system code
SRC += $(PIOSCOMMON)/pios_task_monitor.c
SRC += $(PIOSCOMMON)/pios_callbackscheduler.c