# Conflicts: # UAV-ControlSystem/inc/system_variables.h # UAV-ControlSystem/src/Flight/pid.c # UAV-ControlSystem/src/main.c # UAV-ControlSystem/src/tasks_main.c
243 lines
8.9 KiB
C
243 lines
8.9 KiB
C
/**************************************************************************
|
|
* NAME: scheduler.h *
|
|
* *
|
|
* AUTHOR: Jonas Holmberg *
|
|
* *
|
|
* PURPOSE: Defining the the scheduler to be used in the system to *
|
|
* organize the runtime for the tasks in the system based on *
|
|
* priority. *
|
|
* INFORMATION: Many elements and ideas obtained from beta/cleanflight. *
|
|
* *
|
|
* GLOBAL VARIABLES: *
|
|
* Variable Type Description *
|
|
* -------- ---- ----------- *
|
|
* SystemTasks task_t[] Contains all the tasks that can exist in *
|
|
* the system right now *
|
|
* *
|
|
* averageSystem uint16_t The current load of the system in percent.*
|
|
* LoadPercent May or may not display correctly. *
|
|
* *
|
|
***************************************************************************/
|
|
|
|
#ifndef SCHEDULER_H_
|
|
#define SCHEDULER_H_
|
|
|
|
#include <stdint.h>
|
|
#include "stm32f4xx_revo.h"
|
|
|
|
#define taskAgeCycleCounterSize 16
|
|
|
|
/* Enum containing all the possible task priorities */
|
|
typedef enum
|
|
{
|
|
PRIORITY_IDLE = 0,
|
|
PRIORITY_LOW,
|
|
PRIORITY_MEDIUM,
|
|
PRIORITY_HIGH,
|
|
PRIORITY_REALTIME,
|
|
PRIORITY_MAX_PRIORITY = 255
|
|
} taskPriority_t;
|
|
|
|
|
|
/* struct used to obtain task information */
|
|
typedef struct {
|
|
const char * taskName;
|
|
const char * subTaskName;
|
|
bool isEnabled;
|
|
uint32_t desiredPeriod;
|
|
uint8_t staticPriority;
|
|
uint32_t maxExecutionTime;
|
|
uint32_t totalExecutionTime;
|
|
uint32_t averageExecutionTime;
|
|
uint32_t latestDeltaTime;
|
|
} taskInformation_t;
|
|
|
|
|
|
/* Struct used to contain the information for each task */
|
|
typedef struct
|
|
{
|
|
/* Basic task information */
|
|
const char * taskName; /* Name of the task */
|
|
const char * subTaskName; /*Needed?*/
|
|
bool (*checkEventTriggered)(uint32_t currentDeltaTime); /* Function pointer to event trigger check, if used no standard scheduling */
|
|
void (*taskFunction)(void); /* Pointer to the function that should be called to run the task */
|
|
uint32_t desiredPeriod; /* The period the task wants to run in */
|
|
const uint8_t staticPriority; /* Value used to increment the dynamic priority */
|
|
|
|
/* Scheduling variables */
|
|
uint16_t dynamicPriority; /* Priority increases the longer the task have been idle, increased by staticPriority value */
|
|
uint16_t taskAgeCycle; /* Helps to keep track of the "periods" for the task */
|
|
uint32_t lastExecutedAt; /* last time of invocation */
|
|
uint32_t lastSignaledAt; /* time of invocation event for event-driven tasks */
|
|
|
|
/* Statistic values of the task */
|
|
uint32_t averageExecutionTime; // Moving average over 6 samples, used to calculate guard interval
|
|
uint32_t taskLatestDeltaTime; //
|
|
#ifndef SKIP_TASK_STATISTICS
|
|
uint32_t taskAverageDeltaTime;
|
|
uint32_t maxExecutionTime;
|
|
uint32_t totalExecutionTime; // total time consumed by task since boot
|
|
#endif
|
|
|
|
}task_t;
|
|
|
|
/* Struct used to store statistical data of the scheduler */
|
|
typedef struct
|
|
{
|
|
uint32_t totalSystemRuntime;
|
|
uint32_t totalTaskRuntime; //Total time spent for tasks running
|
|
uint32_t totalOverHead; //Total overhead when selecting a task
|
|
uint32_t averageOverHead;
|
|
uint32_t totalMissedPeriods; //Number of time any task have missed a period
|
|
uint32_t totalSchedulerCalls; //amount of times scheduler have been called
|
|
uint32_t totalTasksScheduled; //the total amount of tasks schedulede
|
|
}scheduler_statistics_t;
|
|
|
|
|
|
/* Task counter, ToDo: If more tasks are needed add them here first, defines are used to make sure the task is somewhere in the system */
|
|
/* Important: If a new define for a task is added here it MUST be added in the tasks.c */
|
|
typedef enum
|
|
{
|
|
/* All the tasks that will be in the system, some are separated by IfDef */
|
|
TASK_SYSTEM = 0,
|
|
TASK_GYROPID,
|
|
TASK_ACCELEROMETER,
|
|
TASK_ATTITUDE,
|
|
TASK_RX,
|
|
TASK_RX_CLI,
|
|
TASK_SERIAL,
|
|
TASK_BATTERY,
|
|
TASK_ARDUINO,
|
|
#ifdef BARO
|
|
TASK_BARO,
|
|
#endif
|
|
#ifdef COMPASS
|
|
TASK_COMPASS,
|
|
#endif
|
|
#ifdef GPS
|
|
TASK_GPS,
|
|
#endif
|
|
#ifdef SONAR
|
|
TASK_SONAR,
|
|
#endif
|
|
#if defined(BARO) || defined(SONAR)
|
|
TASK_ALTITUDE,
|
|
#endif
|
|
#ifdef BEEPER
|
|
TASK_BEEPER,
|
|
#endif
|
|
|
|
//Debug tasks, ONLY to be used when testing
|
|
#ifdef USE_DEBUG_TASKS
|
|
TASK_DEBUG_1,
|
|
TASK_DEBUG_2,
|
|
TASK_DEBUG_3,
|
|
#endif
|
|
|
|
/* Need to be the value directly after the tasks id. Keeps track of the count of the tasks */
|
|
TASK_COUNT,
|
|
|
|
/* Service task IDs */
|
|
TASK_NONE = TASK_COUNT,
|
|
TASK_SELF
|
|
}taskId_t;
|
|
|
|
/* Variables -------------------------------------------------------------*/
|
|
extern scheduler_statistics_t systemSchedulerStatistics;
|
|
extern task_t SystemTasks[TASK_COUNT]; /* All the tasks that exist in the system */
|
|
extern uint16_t averageSystemLoadPercent; /* The average load on the system Todo */
|
|
|
|
|
|
/* Functions that operate can operate on the tasks -----------------------*/
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Enables or disables a task to be able to run in the system.
|
|
*
|
|
* INFORMATION: Given an id for a task it can be added or removed from the
|
|
* active tasks in the system. Meaning tasks that can be selected by the
|
|
* scheduler to run.
|
|
**************************************************************************/
|
|
void enableTask(taskId_t taskId, bool enabled);
|
|
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Returns the delta time value of a task.
|
|
*
|
|
* INFORMATION: Given an id for a task it will return is delta time value.
|
|
* The time between its latest run and the one before.
|
|
**************************************************************************/
|
|
uint32_t getTaskDeltaTime(taskId_t taskId);
|
|
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Gives a task a new period.
|
|
*
|
|
* INFORMATION: Given an id for a task its period can be changed to a new
|
|
* desired value.
|
|
**************************************************************************/
|
|
void rescheduleTask(taskId_t taskId, uint32_t newPeriodMicros);
|
|
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Get some information of a task.
|
|
*
|
|
* INFORMATION: Given an id for a task its current values can be obtain.
|
|
* The variable taskInfo will point to the obtained information
|
|
* and act as an out variable.
|
|
**************************************************************************/
|
|
void getTaskInfo(taskId_t taskId, taskInformation_t * taskInfo);
|
|
|
|
|
|
/* Functions that handle the scheduler ------------------------------------------------------- */
|
|
|
|
/**************************************************************************
|
|
* BRIEF: The main scheduler function.
|
|
*
|
|
* INFORMATION: This function is responsible for choosing the next task that
|
|
* the system should run. This is the main part of the system
|
|
* that will always run, and is the part of the code that will
|
|
* run in each iteration of the system loop.
|
|
**************************************************************************/
|
|
void scheduler(void);
|
|
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Initiates the scheduler and makes it ready to run.
|
|
*
|
|
* INFORMATION: The init will reset the ready queue of the system and add
|
|
* all the tasks that should be added. The tasks that are
|
|
* supposed to run with the current configuration of the system
|
|
**************************************************************************/
|
|
void initScheduler(void);
|
|
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Enables the tasks that should run.
|
|
*
|
|
* INFORMATION: All the tasks in the system that should be added to the run
|
|
* queue will be added when this function is invoked.
|
|
**************************************************************************/
|
|
void initSchedulerTasks(void);
|
|
|
|
|
|
/**************************************************************************
|
|
* BRIEF: Returns an array of ageCyckle values observed when
|
|
* scheduling the tasks.
|
|
*
|
|
* INFORMATION: If a task has an age cycle greater than 1 it means it has
|
|
* missed one or more "periods". Each slot in the 16 value
|
|
* sized array matches a cycle age value observed for a task.
|
|
* Cycle age 1 or less is not counted since it would be to
|
|
* many and we don't care about when it is correct, this is only
|
|
* used to observe how many is wrong. Every task will generate
|
|
* a age cycle value each scheduling attempt. Each time a task
|
|
* missed his period the values in the array that this function
|
|
* return will increase.
|
|
**************************************************************************/
|
|
#ifdef USE_TASK_AGE_CYCLE_STATISTICS
|
|
void getSchedulerAgeCycleData(uint32_t outValue[taskAgeCycleCounterSize]);
|
|
#endif
|
|
|
|
|
|
#endif /* SCHEDULER_H_ */
|