Preparation before merge
This commit is contained in:
parent
94e5472817
commit
bab2c72ae0
|
@ -666,19 +666,18 @@ int main(void) {
|
|||
rescheduleTask(TASK_GYROPID, targetLooptime);
|
||||
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
setTaskEnabled(TASK_MOTOR, true);
|
||||
rescheduleTask(TASK_MOTOR, lrintf((1.0f / masterConfig.motor_pwm_rate) * 1000000));
|
||||
|
||||
if(sensors(SENSOR_ACC)) {
|
||||
setTaskEnabled(TASK_ACCEL, true);
|
||||
switch(targetLooptime) { // Switch statement kept in place to change acc rates in the future
|
||||
case(500):
|
||||
case(375):
|
||||
case(250):
|
||||
case(125):
|
||||
accTargetLooptime = 1000;
|
||||
break;
|
||||
default:
|
||||
case(1000):
|
||||
case(500):
|
||||
case(375):
|
||||
case(250):
|
||||
case(125):
|
||||
accTargetLooptime = 1000;
|
||||
break;
|
||||
default:
|
||||
case(1000):
|
||||
#ifdef STM32F10X
|
||||
accTargetLooptime = 3000;
|
||||
#else
|
||||
|
@ -687,8 +686,11 @@ int main(void) {
|
|||
}
|
||||
rescheduleTask(TASK_ACCEL, accTargetLooptime);
|
||||
}
|
||||
setTaskEnabled(TASK_ACCEL, sensors(SENSOR_ACC));
|
||||
setTaskEnabled(TASK_SERIAL, true);
|
||||
#ifdef BEEPER
|
||||
setTaskEnabled(TASK_BEEPER, true);
|
||||
#endif
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
|
||||
setTaskEnabled(TASK_RX, true);
|
||||
#ifdef GPS
|
||||
|
@ -711,15 +713,12 @@ int main(void) {
|
|||
#endif
|
||||
#ifdef TELEMETRY
|
||||
setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
|
||||
// Reschedule telemetry to 500hz for Jeti Exbus
|
||||
if (feature(FEATURE_TELEMETRY) || masterConfig.rxConfig.serialrx_provider == SERIALRX_JETIEXBUS) rescheduleTask(TASK_TELEMETRY, 2000);
|
||||
#endif
|
||||
#ifdef LED_STRIP
|
||||
setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP));
|
||||
#endif
|
||||
#ifdef USE_BST
|
||||
setTaskEnabled(TASK_BST_READ_WRITE, true);
|
||||
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
||||
#ifdef TRANSPONDER
|
||||
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
|
||||
#endif
|
||||
|
||||
while (1) {
|
||||
|
@ -731,9 +730,17 @@ int main(void) {
|
|||
void HardFault_Handler(void)
|
||||
{
|
||||
// fall out of the sky
|
||||
uint8_t requiredState = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY;
|
||||
if ((systemState & requiredState) == requiredState) {
|
||||
uint8_t requiredStateForMotors = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY;
|
||||
if ((systemState & requiredStateForMotors) == requiredStateForMotors) {
|
||||
stopMotors();
|
||||
}
|
||||
#ifdef TRANSPONDER
|
||||
// prevent IR LEDs from burning out.
|
||||
uint8_t requiredStateForTransponder = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_TRANSPONDER_ENABLED;
|
||||
if ((systemState & requiredStateForTransponder) == requiredStateForTransponder) {
|
||||
transponderIrDisable();
|
||||
}
|
||||
#endif
|
||||
|
||||
while (1);
|
||||
}
|
||||
|
|
|
@ -15,11 +15,14 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define SRC_MAIN_SCHEDULER_C_
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include <platform.h>
|
||||
|
||||
#include "scheduler.h"
|
||||
#include "debug.h"
|
||||
|
||||
|
@ -27,218 +30,23 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
|
||||
//#define SCHEDULER_DEBUG
|
||||
|
||||
cfTaskId_e currentTaskId = TASK_NONE;
|
||||
|
||||
#define REALTIME_GUARD_INTERVAL_MIN 10
|
||||
#define REALTIME_GUARD_INTERVAL_MAX 300
|
||||
#define REALTIME_GUARD_INTERVAL_MARGIN 25
|
||||
|
||||
static uint32_t totalWaitingTasks;
|
||||
static uint32_t totalWaitingTasksSamples;
|
||||
|
||||
bool realTimeCycle = true;
|
||||
static uint32_t realtimeGuardInterval = REALTIME_GUARD_INTERVAL_MAX;
|
||||
|
||||
uint32_t currentTime = 0;
|
||||
uint16_t averageWaitingTasks100 = 0;
|
||||
|
||||
typedef struct {
|
||||
/* Configuration */
|
||||
const char * taskName;
|
||||
const char * subTaskName; // For future use, but now just for naming convention
|
||||
bool (*checkFunc)(uint32_t currentDeltaTime);
|
||||
void (*taskFunc)(void);
|
||||
bool isEnabled;
|
||||
uint32_t desiredPeriod; // target period of execution
|
||||
uint8_t staticPriority; // dynamicPriority grows in steps of this size, shouldn't be zero
|
||||
|
||||
/* Scheduling */
|
||||
uint8_t dynamicPriority; // measurement of how old task was last executed, used to avoid task starvation
|
||||
uint32_t lastExecutedAt; // last time of invocation
|
||||
uint32_t lastSignaledAt; // time of invocation event for event-driven tasks
|
||||
uint16_t taskAgeCycles;
|
||||
|
||||
/* Statistics */
|
||||
uint32_t averageExecutionTime; // Moving averate over 6 samples, used to calculate guard interval
|
||||
uint32_t taskLatestDeltaTime; //
|
||||
#ifndef SKIP_TASK_STATISTICS
|
||||
uint32_t maxExecutionTime;
|
||||
uint32_t totalExecutionTime; // total time consumed by task since boot
|
||||
#endif
|
||||
} cfTask_t;
|
||||
|
||||
void taskMainPidLoopCheck(void);
|
||||
void taskMotorUpdate(void);
|
||||
void taskUpdateAccelerometer(void);
|
||||
void taskHandleSerial(void);
|
||||
void taskUpdateBeeper(void);
|
||||
void taskUpdateBattery(void);
|
||||
bool taskUpdateRxCheck(uint32_t currentDeltaTime);
|
||||
void taskUpdateRxMain(void);
|
||||
void taskProcessGPS(void);
|
||||
void taskUpdateCompass(void);
|
||||
void taskUpdateBaro(void);
|
||||
void taskUpdateSonar(void);
|
||||
void taskCalculateAltitude(void);
|
||||
void taskUpdateDisplay(void);
|
||||
void taskTelemetry(void);
|
||||
void taskLedStrip(void);
|
||||
void taskSystem(void);
|
||||
#ifdef USE_BST
|
||||
void taskBstReadWrite(void);
|
||||
void taskBstMasterProcess(void);
|
||||
#endif
|
||||
|
||||
static cfTask_t cfTasks[TASK_COUNT] = {
|
||||
[TASK_SYSTEM] = {
|
||||
.isEnabled = true,
|
||||
.taskName = "SYSTEM",
|
||||
.taskFunc = taskSystem,
|
||||
.desiredPeriod = 1000000 / 10, // run every 100 ms
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
[TASK_GYROPID] = {
|
||||
.taskName = "PID",
|
||||
.subTaskName = "GYRO",
|
||||
.taskFunc = taskMainPidLoopCheck,
|
||||
.desiredPeriod = 1000,
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
[TASK_MOTOR] = {
|
||||
.taskName = "MOTOR",
|
||||
.taskFunc = taskMotorUpdate,
|
||||
.desiredPeriod = 1000,
|
||||
.staticPriority = TASK_PRIORITY_REALTIME,
|
||||
},
|
||||
|
||||
[TASK_ACCEL] = {
|
||||
.taskName = "ACCEL",
|
||||
.taskFunc = taskUpdateAccelerometer,
|
||||
.desiredPeriod = 1000000 / 100,
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
|
||||
[TASK_SERIAL] = {
|
||||
.taskName = "SERIAL",
|
||||
.taskFunc = taskHandleSerial,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
|
||||
[TASK_BEEPER] = {
|
||||
.taskName = "BEEPER",
|
||||
.taskFunc = taskUpdateBeeper,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
|
||||
[TASK_BATTERY] = {
|
||||
.taskName = "BATTERY",
|
||||
.taskFunc = taskUpdateBattery,
|
||||
.desiredPeriod = 1000000 / 50, // 50 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
|
||||
[TASK_RX] = {
|
||||
.taskName = "RX",
|
||||
.checkFunc = taskUpdateRxCheck,
|
||||
.taskFunc = taskUpdateRxMain,
|
||||
.desiredPeriod = 1000000 / 50, // If event-based scheduling doesn't work, fallback to periodic scheduling
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
#ifdef GPS
|
||||
[TASK_GPS] = {
|
||||
.taskName = "GPS",
|
||||
.taskFunc = taskProcessGPS,
|
||||
.desiredPeriod = 1000000 / 10, // GPS usually don't go raster than 10Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
[TASK_COMPASS] = {
|
||||
.taskName = "COMPASS",
|
||||
.taskFunc = taskUpdateCompass,
|
||||
.desiredPeriod = 1000000 / 10, // Compass is updated at 10 Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
[TASK_BARO] = {
|
||||
.taskName = "BARO",
|
||||
.taskFunc = taskUpdateBaro,
|
||||
.desiredPeriod = 1000000 / 20,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
[TASK_SONAR] = {
|
||||
.taskName = "SONAR",
|
||||
.taskFunc = taskUpdateSonar,
|
||||
.desiredPeriod = 1000000 / 20,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
[TASK_ALTITUDE] = {
|
||||
.taskName = "ALTITUDE",
|
||||
.taskFunc = taskCalculateAltitude,
|
||||
.desiredPeriod = 1000000 / 40,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef DISPLAY
|
||||
[TASK_DISPLAY] = {
|
||||
.taskName = "DISPLAY",
|
||||
.taskFunc = taskUpdateDisplay,
|
||||
.desiredPeriod = 1000000 / 10,
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef TELEMETRY
|
||||
[TASK_TELEMETRY] = {
|
||||
.taskName = "TELEMETRY",
|
||||
.taskFunc = taskTelemetry,
|
||||
.desiredPeriod = 1000000 / 250, // 250 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef LED_STRIP
|
||||
[TASK_LEDSTRIP] = {
|
||||
.taskName = "LEDSTRIP",
|
||||
.taskFunc = taskLedStrip,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_BST
|
||||
[TASK_BST_READ_WRITE] = {
|
||||
.taskName = "BST_MASTER_WRITE",
|
||||
.taskFunc = taskBstReadWrite,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
|
||||
[TASK_BST_MASTER_PROCESS] = {
|
||||
.taskName = "BST_MASTER_PROCESS",
|
||||
.taskFunc = taskBstMasterProcess,
|
||||
.desiredPeriod = 1000000 / 50, // 50 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
uint16_t averageSystemLoadPercent = 0;
|
||||
|
||||
|
||||
void taskSystem(void)
|
||||
{
|
||||
uint8_t taskId;
|
||||
|
||||
/* Calculate system load */
|
||||
if (totalWaitingTasksSamples > 0) {
|
||||
|
@ -246,20 +54,31 @@ void taskSystem(void)
|
|||
totalWaitingTasksSamples = 0;
|
||||
totalWaitingTasks = 0;
|
||||
}
|
||||
|
||||
/* Calculate guard interval */
|
||||
uint32_t maxNonRealtimeTaskTime = 0;
|
||||
for (taskId = 0; taskId < TASK_COUNT; taskId++) {
|
||||
if (cfTasks[taskId].staticPriority != TASK_PRIORITY_REALTIME) {
|
||||
maxNonRealtimeTaskTime = MAX(maxNonRealtimeTaskTime, cfTasks[taskId].averageExecutionTime);
|
||||
}
|
||||
}
|
||||
|
||||
realtimeGuardInterval = constrain(maxNonRealtimeTaskTime, REALTIME_GUARD_INTERVAL_MIN, REALTIME_GUARD_INTERVAL_MAX) + REALTIME_GUARD_INTERVAL_MARGIN;
|
||||
#if defined SCHEDULER_DEBUG
|
||||
debug[2] = realtimeGuardInterval;
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifndef SKIP_TASK_STATISTICS
|
||||
void getTaskInfo(cfTaskId_e taskId, cfTaskInfo_t * taskInfo)
|
||||
{
|
||||
taskInfo->taskName = cfTasks[taskId].taskName;
|
||||
taskInfo->subTaskName = cfTasks[taskId].subTaskName;
|
||||
taskInfo->isEnabled= cfTasks[taskId].isEnabled;
|
||||
taskInfo->desiredPeriod = cfTasks[taskId].desiredPeriod;
|
||||
taskInfo->staticPriority = cfTasks[taskId].staticPriority;
|
||||
taskInfo->maxExecutionTime = cfTasks[taskId].maxExecutionTime;
|
||||
taskInfo->totalExecutionTime = cfTasks[taskId].totalExecutionTime;
|
||||
taskInfo->averageExecutionTime = cfTasks[taskId].averageExecutionTime;
|
||||
taskInfo->latestDeltaTime = cfTasks[taskId].taskLatestDeltaTime;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -296,24 +115,19 @@ uint32_t getTaskDeltaTime(cfTaskId_e taskId)
|
|||
}
|
||||
}
|
||||
|
||||
#define MAXT_TIME_TICKS_TO_RESET 10000
|
||||
|
||||
void scheduler(void)
|
||||
{
|
||||
static uint16_t maxTaskCalculationReset = MAXT_TIME_TICKS_TO_RESET;
|
||||
uint8_t taskId;
|
||||
uint8_t selectedTaskId;
|
||||
uint8_t selectedTaskDynPrio;
|
||||
/* The task to be invoked */
|
||||
uint8_t selectedTaskId = TASK_NONE;
|
||||
uint8_t selectedTaskDynPrio = 0;
|
||||
uint16_t waitingTasks = 0;
|
||||
uint32_t timeToNextRealtimeTask = UINT32_MAX;
|
||||
|
||||
SET_SCHEDULER_LOCALS();
|
||||
/* Cache currentTime */
|
||||
currentTime = micros();
|
||||
|
||||
/* The task to be invoked */
|
||||
selectedTaskId = TASK_NONE;
|
||||
selectedTaskDynPrio = 0;
|
||||
|
||||
/* Check for realtime tasks */
|
||||
for (taskId = 0; taskId < TASK_COUNT; taskId++) {
|
||||
if (cfTasks[taskId].staticPriority == TASK_PRIORITY_REALTIME) {
|
||||
|
@ -328,7 +142,7 @@ void scheduler(void)
|
|||
}
|
||||
}
|
||||
|
||||
bool outsideRealtimeGuardInterval = (timeToNextRealtimeTask > 0);
|
||||
bool outsideRealtimeGuardInterval = (timeToNextRealtimeTask > realtimeGuardInterval);
|
||||
|
||||
/* Update task dynamic priorities */
|
||||
for (taskId = 0; taskId < TASK_COUNT; taskId++) {
|
||||
|
@ -399,13 +213,7 @@ void scheduler(void)
|
|||
cfTasks[selectedTaskId].averageExecutionTime = ((uint32_t)cfTasks[selectedTaskId].averageExecutionTime * 31 + taskExecutionTime) / 32;
|
||||
#ifndef SKIP_TASK_STATISTICS
|
||||
cfTasks[selectedTaskId].totalExecutionTime += taskExecutionTime; // time consumed by scheduler + task
|
||||
if (maxTaskCalculationReset > 0) {
|
||||
cfTasks[selectedTaskId].maxExecutionTime = MAX(cfTasks[selectedTaskId].maxExecutionTime, taskExecutionTime);
|
||||
maxTaskCalculationReset--;
|
||||
} else {
|
||||
cfTasks[selectedTaskId].maxExecutionTime = taskExecutionTime;
|
||||
maxTaskCalculationReset = MAXT_TIME_TICKS_TO_RESET;
|
||||
}
|
||||
cfTasks[selectedTaskId].maxExecutionTime = MAX(cfTasks[selectedTaskId].maxExecutionTime, taskExecutionTime);
|
||||
#endif
|
||||
#if defined SCHEDULER_DEBUG
|
||||
debug[3] = (micros() - currentTime) - taskExecutionTime;
|
||||
|
@ -417,4 +225,5 @@ void scheduler(void)
|
|||
debug[3] = (micros() - currentTime);
|
||||
#endif
|
||||
}
|
||||
GET_SCHEDULER_LOCALS();
|
||||
}
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
//#define SCHEDULER_DEBUG
|
||||
|
||||
typedef enum {
|
||||
TASK_PRIORITY_IDLE = 0, // Disables dynamic scheduling, task is executed only if no other task is active this cycle
|
||||
TASK_PRIORITY_LOW = 1,
|
||||
|
@ -28,25 +30,23 @@ typedef enum {
|
|||
|
||||
typedef struct {
|
||||
const char * taskName;
|
||||
const char * subTaskName;
|
||||
bool isEnabled;
|
||||
uint32_t desiredPeriod;
|
||||
uint8_t staticPriority;
|
||||
uint32_t maxExecutionTime;
|
||||
uint32_t totalExecutionTime;
|
||||
uint32_t lastExecutionTime;
|
||||
uint32_t averageExecutionTime;
|
||||
uint32_t latestDeltaTime;
|
||||
} cfTaskInfo_t;
|
||||
|
||||
typedef enum {
|
||||
/* Actual tasks */
|
||||
TASK_SYSTEM = 0,
|
||||
TASK_GYROPID,
|
||||
TASK_MOTOR,
|
||||
TASK_ACCEL,
|
||||
TASK_SERIAL,
|
||||
#ifdef BEEPER
|
||||
TASK_BEEPER,
|
||||
#endif
|
||||
TASK_BATTERY,
|
||||
TASK_RX,
|
||||
#ifdef GPS
|
||||
|
@ -73,9 +73,8 @@ typedef enum {
|
|||
#ifdef LED_STRIP
|
||||
TASK_LEDSTRIP,
|
||||
#endif
|
||||
#ifdef USE_BST
|
||||
TASK_BST_READ_WRITE,
|
||||
TASK_BST_MASTER_PROCESS,
|
||||
#ifdef TRANSPONDER
|
||||
TASK_TRANSPONDER,
|
||||
#endif
|
||||
|
||||
/* Count of real tasks */
|
||||
|
@ -86,6 +85,31 @@ typedef enum {
|
|||
TASK_SELF
|
||||
} cfTaskId_e;
|
||||
|
||||
typedef struct {
|
||||
/* Configuration */
|
||||
const char * taskName;
|
||||
bool (*checkFunc)(uint32_t currentDeltaTime);
|
||||
void (*taskFunc)(void);
|
||||
bool isEnabled;
|
||||
uint32_t desiredPeriod; // target period of execution
|
||||
uint8_t staticPriority; // dynamicPriority grows in steps of this size, shouldn't be zero
|
||||
|
||||
/* Scheduling */
|
||||
uint8_t dynamicPriority; // measurement of how old task was last executed, used to avoid task starvation
|
||||
uint32_t lastExecutedAt; // last time of invocation
|
||||
uint32_t lastSignaledAt; // time of invocation event for event-driven tasks
|
||||
uint16_t taskAgeCycles;
|
||||
|
||||
/* Statistics */
|
||||
uint32_t averageExecutionTime; // Moving averate over 6 samples, used to calculate guard interval
|
||||
uint32_t taskLatestDeltaTime; //
|
||||
#ifndef SKIP_TASK_STATISTICS
|
||||
uint32_t maxExecutionTime;
|
||||
uint32_t totalExecutionTime; // total time consumed by task since boot
|
||||
#endif
|
||||
} cfTask_t;
|
||||
|
||||
extern cfTask_t cfTasks[TASK_COUNT];
|
||||
extern uint16_t cpuLoad;
|
||||
extern uint16_t averageSystemLoadPercent;
|
||||
|
||||
|
@ -95,3 +119,7 @@ void setTaskEnabled(cfTaskId_e taskId, bool newEnabledState);
|
|||
uint32_t getTaskDeltaTime(cfTaskId_e taskId);
|
||||
|
||||
void scheduler(void);
|
||||
|
||||
#define LOAD_PERCENTAGE_ONE 100
|
||||
|
||||
#define isSystemOverloaded() (averageSystemLoadPercent >= LOAD_PERCENTAGE_ONE)
|
||||
|
|
|
@ -0,0 +1,177 @@
|
|||
/*
|
||||
* 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 <stdlib.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "scheduler.h"
|
||||
|
||||
void taskMainPidLoopChecker(void);
|
||||
void taskUpdateAccelerometer(void);
|
||||
void taskHandleSerial(void);
|
||||
void taskUpdateBeeper(void);
|
||||
void taskUpdateBattery(void);
|
||||
bool taskUpdateRxCheck(uint32_t currentDeltaTime);
|
||||
void taskUpdateRxMain(void);
|
||||
void taskProcessGPS(void);
|
||||
void taskUpdateCompass(void);
|
||||
void taskUpdateBaro(void);
|
||||
void taskUpdateSonar(void);
|
||||
void taskCalculateAltitude(void);
|
||||
void taskUpdateDisplay(void);
|
||||
void taskTelemetry(void);
|
||||
void taskLedStrip(void);
|
||||
void taskTransponder(void);
|
||||
void taskSystem(void);
|
||||
|
||||
cfTask_t cfTasks[TASK_COUNT] = {
|
||||
[TASK_SYSTEM] = {
|
||||
.isEnabled = true,
|
||||
.taskName = "SYSTEM",
|
||||
.taskFunc = taskSystem,
|
||||
.desiredPeriod = 1000000 / 10, // run every 100 ms
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
[TASK_GYROPID] = {
|
||||
.taskName = "GYRO/PID",
|
||||
.taskFunc = taskMainPidLoopChecker,
|
||||
.desiredPeriod = 1000,
|
||||
.staticPriority = TASK_PRIORITY_REALTIME,
|
||||
},
|
||||
|
||||
[TASK_ACCEL] = {
|
||||
.taskName = "ACCEL",
|
||||
.taskFunc = taskUpdateAccelerometer,
|
||||
.desiredPeriod = 1000000 / 100, // every 10ms
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
[TASK_SERIAL] = {
|
||||
.taskName = "SERIAL",
|
||||
.taskFunc = taskHandleSerial,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
|
||||
#ifdef BEEPER
|
||||
[TASK_BEEPER] = {
|
||||
.taskName = "BEEPER",
|
||||
.taskFunc = taskUpdateBeeper,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
[TASK_BATTERY] = {
|
||||
.taskName = "BATTERY",
|
||||
.taskFunc = taskUpdateBattery,
|
||||
.desiredPeriod = 1000000 / 50, // 50 Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
[TASK_RX] = {
|
||||
.taskName = "RX",
|
||||
.checkFunc = taskUpdateRxCheck,
|
||||
.taskFunc = taskUpdateRxMain,
|
||||
.desiredPeriod = 1000000 / 50, // If event-based scheduling doesn't work, fallback to periodic scheduling
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
|
||||
#ifdef GPS
|
||||
[TASK_GPS] = {
|
||||
.taskName = "GPS",
|
||||
.taskFunc = taskProcessGPS,
|
||||
.desiredPeriod = 1000000 / 10, // GPS usually don't go raster than 10Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
[TASK_COMPASS] = {
|
||||
.taskName = "COMPASS",
|
||||
.taskFunc = taskUpdateCompass,
|
||||
.desiredPeriod = 1000000 / 10, // Compass is updated at 10 Hz
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
[TASK_BARO] = {
|
||||
.taskName = "BARO",
|
||||
.taskFunc = taskUpdateBaro,
|
||||
.desiredPeriod = 1000000 / 20,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
[TASK_SONAR] = {
|
||||
.taskName = "SONAR",
|
||||
.taskFunc = taskUpdateSonar,
|
||||
.desiredPeriod = 1000000 / 20,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
[TASK_ALTITUDE] = {
|
||||
.taskName = "ALTITUDE",
|
||||
.taskFunc = taskCalculateAltitude,
|
||||
.desiredPeriod = 1000000 / 40,
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
[TASK_TRANSPONDER] = {
|
||||
.taskName = "TRANSPONDER",
|
||||
.taskFunc = taskTransponder,
|
||||
.desiredPeriod = 1000000 / 250, // 250 Hz
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef DISPLAY
|
||||
[TASK_DISPLAY] = {
|
||||
.taskName = "DISPLAY",
|
||||
.taskFunc = taskUpdateDisplay,
|
||||
.desiredPeriod = 1000000 / 10,
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef TELEMETRY
|
||||
[TASK_TELEMETRY] = {
|
||||
.taskName = "TELEMETRY",
|
||||
.taskFunc = taskTelemetry,
|
||||
.desiredPeriod = 1000000 / 250, // 250 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef LED_STRIP
|
||||
[TASK_LEDSTRIP] = {
|
||||
.taskName = "LEDSTRIP",
|
||||
.taskFunc = taskLedStrip,
|
||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
};
|
Loading…
Reference in New Issue