STM32F4: Platform defines and common system file placement

This commit is contained in:
blckmn 2016-06-08 06:53:40 +10:00
parent bef18e4fd7
commit 3582e459a4
8 changed files with 1294 additions and 12 deletions

View File

@ -246,7 +246,8 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(USBFS_DIR)/inc \
$(CMSIS_DIR)/CM4/CoreSupport \
$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
$(ROOT)/src/main/vcpf4
$(ROOT)/src/main/vcpf4 \
$(ROOT)/src/main/platform
ifeq ($(TARGET),$(filter $(TARGET),$(SDCARD_TARGETS)))
INCLUDE_DIRS := $(INCLUDE_DIRS) \
@ -512,7 +513,7 @@ STM32F30x_COMMON_SRC = \
drivers/adc_stm32f30x.c \
drivers/bus_i2c_stm32f30x.c \
drivers/bus_spi.c \
drivers/display_ug2864hsweg01.h \
drivers/display_ug2864hsweg01.c \
drivers/gpio_stm32f30x.c \
drivers/light_led.c \
drivers/pwm_mapping.c \
@ -527,6 +528,7 @@ STM32F30x_COMMON_SRC = \
STM32F4xx_COMMON_SRC = \
startup_stm32f40xx.s \
platform/system_stm32f4xx.c \
drivers/accgyro_mpu.c \
drivers/adc.c \
drivers/adc_stm32f4xx.c \
@ -567,7 +569,7 @@ NAZE_SRC = \
drivers/barometer_ms5611.c \
drivers/barometer_bmp280.c \
drivers/compass_hmc5883l.c \
drivers/display_ug2864hsweg01.h \
drivers/display_ug2864hsweg01.c \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f10x.c \

View File

@ -164,3 +164,5 @@ bool isMPUSoftReset(void)
else
return false;
}

View File

@ -22,6 +22,7 @@
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_gpio.h"
#include "core_cm4.h"
#include "common_stm32f4xx.h"
// Chip Unique ID on F405
#define U_ID_0 (*(uint32_t*)0x1fff7a10)

View File

@ -0,0 +1,5 @@
/*
Common defines applicable to STM32F4
*/
#define TASK_GYROPID_DESIRED_PERIOD 125

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,45 @@
/**
******************************************************************************
* @file system_stm32f4xx.h
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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.
*
******************************************************************************
*/
#ifndef __SYSTEM_STM32F4XX_H
#define __SYSTEM_STM32F4XX_H
#ifdef __cplusplus
extern "C" {
#endif
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F4XX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -31,9 +31,8 @@
#include "drivers/system.h"
#if defined (STM32F4)
#define DELAY_LIMIT 10
#else #define DELAY_LIMIT 100
#ifndef SCHEDULER_DELAY_LIMIT
#define SCHEDULER_DELAY_LIMIT 100
#endif
static cfTask_t *currentTask = NULL;
@ -142,7 +141,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros)
{
if (taskId == TASK_SELF || taskId < TASK_COUNT) {
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
task->desiredPeriod = MAX(DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging
}
}

View File

@ -45,6 +45,10 @@ void taskBstReadWrite(void);
void taskBstMasterProcess(void);
#endif
#ifndef TASK_GYROPID_DESIRED_PERIOD
#define TASK_GYROPID_DESIRED_PERIOD 1000
#endif
cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SYSTEM] = {
.taskName = "SYSTEM",
@ -57,11 +61,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.taskName = "PID",
.subTaskName = "GYRO",
.taskFunc = taskMainPidLoopCheck,
#if defined(STM32F4)
.desiredPeriod = 125,
#else
.desiredPeriod = 1000,
#endif
.desiredPeriod = TASK_GYROPID_DESIRED_PERIOD,
.staticPriority = TASK_PRIORITY_REALTIME,
},