1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 08:15:26 +03:00

More fixes to time types

This commit is contained in:
Konstantin Sharlaimov (DigitalEntity) 2017-01-15 19:24:35 +10:00
parent e7dd693dd5
commit adaef0da5a
28 changed files with 99 additions and 95 deletions

View file

@ -24,15 +24,16 @@ extern uint8_t debugMode;
#define DEBUG_SECTION_TIMES
#ifdef DEBUG_SECTION_TIMES
extern uint32_t sectionTimes[2][4];
#include "common/time.h"
extern timeUs_t sectionTimes[2][4];
#define TIME_SECTION_BEGIN(index) { \
extern uint32_t sectionTimes[2][4]; \
extern timeUs_t sectionTimes[2][4]; \
sectionTimes[0][index] = micros(); \
}
#define TIME_SECTION_END(index) { \
extern uint32_t sectionTimes[2][4]; \
extern timeUs_t sectionTimes[2][4]; \
sectionTimes[1][index] = micros(); \
debug[index] = sectionTimes[1][index] - sectionTimes[0][index]; \
}

View file

@ -215,9 +215,9 @@ static void mpuIntExtiHandler(extiCallbackRec_t *cb)
gyro->dataReady = true;
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
static uint32_t lastCalledAt = 0;
uint32_t now = micros();
uint32_t callDelta = now - lastCalledAt;
static timeUs_t lastCalledAt = 0;
timeUs_t now = micros();
timeUs_t callDelta = now - lastCalledAt;
debug[0] = callDelta;
lastCalledAt = now;
#endif

View file

@ -88,7 +88,7 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f };
typedef struct queuedReadState_s {
bool waiting;
uint8_t len;
uint32_t readStartedAt; // time read was queued in micros.
timeUs_t readStartedAt; // time read was queued in micros.
} queuedReadState_t;
typedef enum {
@ -138,15 +138,15 @@ static bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
return true;
}
static uint32_t ak8963SensorQueuedReadTimeRemaining(void)
static timeDelta_t ak8963SensorQueuedReadTimeRemaining(void)
{
if (!queuedRead.waiting) {
return 0;
}
int32_t timeSinceStarted = micros() - queuedRead.readStartedAt;
timeDelta_t timeSinceStarted = micros() - queuedRead.readStartedAt;
int32_t timeRemaining = 8000 - timeSinceStarted;
timeDelta_t timeRemaining = 8000 - timeSinceStarted;
if (timeRemaining < 0) {
return 0;
@ -157,7 +157,7 @@ static uint32_t ak8963SensorQueuedReadTimeRemaining(void)
static bool ak8963SensorCompleteRead(uint8_t *buf)
{
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
timeDelta_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining > 0) {
delayMicroseconds(timeRemaining);

View file

@ -83,7 +83,7 @@ typedef struct sdcard_t {
uint32_t callbackData;
#ifdef SDCARD_PROFILING
uint32_t profileStartTime;
timeUs_t profileStartTime;
#endif
} pendingOperation;

View file

@ -96,7 +96,7 @@
#include "hardware_revision.h"
#endif
extern timeUs_t cycleTime; // FIXME dependency on mw.c
extern timeDelta_t cycleTime; // FIXME dependency on mw.c
extern uint16_t rssi; // FIXME dependency on mw.c
static const char * const flightControllerIdentifier = INAV_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.

View file

@ -22,7 +22,7 @@
#include "common/time.h"
void taskMainPidLoopChecker(timeUs_t currentTimeUs);
bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeUs_t currentDeltaTime);
bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime);
void taskUpdateRxMain(timeUs_t currentTimeUs);
void taskSystem(timeUs_t currentTimeUs);

View file

@ -90,7 +90,7 @@ enum {
#define GYRO_WATCHDOG_DELAY 100 // Watchdog for boards without interrupt for gyro
timeUs_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
timeDelta_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
float dT;
@ -528,7 +528,7 @@ void filterRc(bool isRXDataNew)
filterInitialised = true;
}
const timeUs_t filteredCycleTime = biquadFilterApply(&filteredCycleTimeState, (float) cycleTime);
const timeDelta_t filteredCycleTime = biquadFilterApply(&filteredCycleTimeState, (float) cycleTime);
rcInterpolationFactor = rxGetRefreshRate() / filteredCycleTime + 1;
if (isRXDataNew) {
@ -556,14 +556,14 @@ void filterRc(bool isRXDataNew)
void taskGyro(timeUs_t currentTimeUs) {
// getTaskDeltaTime() returns delta time freezed at the moment of entering the scheduler. currentTime is freezed at the very same point.
// To make busy-waiting timeout work we need to account for time spent within busy-waiting loop
const timeUs_t currentDeltaTime = getTaskDeltaTime(TASK_SELF);
const timeDelta_t currentDeltaTime = getTaskDeltaTime(TASK_SELF);
if (gyroConfig()->gyroSync) {
while (true) {
#ifdef ASYNC_GYRO_PROCESSING
if (gyroSyncCheckUpdate(&gyro.dev) || ((currentDeltaTime + (micros() - currentTimeUs)) >= (getGyroUpdateRate() + GYRO_WATCHDOG_DELAY))) {
if (gyroSyncCheckUpdate(&gyro.dev) || (((timeUs_t)currentDeltaTime + (micros() - currentTimeUs)) >= (getGyroUpdateRate() + GYRO_WATCHDOG_DELAY))) {
#else
if (gyroSyncCheckUpdate(&gyro.dev) || ((currentDeltaTime + (micros() - currentTimeUs)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) {
if (gyroSyncCheckUpdate(&gyro.dev) || (((timeUs_t)currentDeltaTime + (micros() - currentTimeUs)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) {
#endif
break;
}
@ -575,7 +575,7 @@ void taskGyro(timeUs_t currentTimeUs) {
#ifdef ASYNC_GYRO_PROCESSING
/* Update IMU for better accuracy */
imuUpdateGyroscope(currentDeltaTime + (micros() - currentTimeUs));
imuUpdateGyroscope((timeUs_t)currentDeltaTime + (micros() - currentTimeUs));
#endif
}
@ -709,7 +709,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
}
bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeUs_t currentDeltaTime)
bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
{
UNUSED(currentDeltaTime);

View file

@ -110,7 +110,7 @@ uint8_t cliMode = 0;
#define PLAY_SOUND
#endif
extern timeUs_t cycleTime; // FIXME dependency on mw.c
extern timeDelta_t cycleTime; // FIXME dependency on mw.c
extern uint8_t detectedSensors[SENSOR_INDEX_COUNT];
static serialPort_t *cliPort;

View file

@ -129,7 +129,7 @@ static const char* const gpsFixTypeText[] = {
static const char* tickerCharacters = "|/-\\"; // use 2/4/8 characters so that the divide is optimal.
#define TICKER_CHARACTER_COUNT (sizeof(tickerCharacters) / sizeof(char))
static uint32_t nextPageAt;
static timeUs_t nextPageAt;
static bool forcePageChange;
static pageId_e currentPageId;
@ -486,13 +486,13 @@ void dashboardInit(void)
#endif
dashboardSetPage(PAGE_WELCOME);
const uint32_t now = micros();
const timeUs_t now = micros();
dashboardSetNextPageChangeAt(now + 5 * MICROSECONDS_IN_A_SECOND);
dashboardUpdate(now);
}
void dashboardSetNextPageChangeAt(uint32_t futureMicros)
void dashboardSetNextPageChangeAt(timeUs_t futureMicros)
{
nextPageAt = futureMicros;
}

View file

@ -74,10 +74,10 @@
static int suart_getc(void)
{
uint32_t btime;
uint32_t start_time;
timeUs_t btime;
timeUs_t start_time;
uint32_t wait_time = micros() + START_BIT_TIMEOUT;
timeUs_t wait_time = micros() + START_BIT_TIMEOUT;
while (ESC_IS_HI) {
// check for startbit begin
if (micros() >= wait_time) {
@ -89,7 +89,7 @@ static int suart_getc(void)
btime = start_time + START_BIT_TIME;
uint16_t bitmask = 0;
for(int bit = 0; bit < 10; bit++) {
while (cmp32(micros(), btime) < 0);
while (cmpTimeUs(micros(), btime) < 0);
if (ESC_IS_HI)
bitmask |= (1 << bit);
btime = btime + BIT_TIME;
@ -105,7 +105,7 @@ static void suart_putc(uint8_t byte)
{
// send one idle bit first (stopbit from previous byte)
uint16_t bitmask = (byte << 2) | (1 << 0) | (1 << 10);
uint32_t btime = micros();
timeUs_t btime = micros();
while(1) {
if(bitmask & 1)
ESC_SET_HI; // 1
@ -115,7 +115,7 @@ static void suart_putc(uint8_t byte)
bitmask >>= 1;
if (bitmask == 0)
break; // stopbit shifted out - but don't wait
while (cmp32(micros(), btime) < 0);
while (cmpTimeUs(micros(), btime) < 0);
}
}

View file

@ -54,10 +54,10 @@ static uint8_t stkInBuf[16];
#define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5ms
#define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) // 5s
#define WaitPinLo while (ESC_IS_HI) { if (cmp32(micros(), timeout_timer) > 0) goto timeout; }
#define WaitPinHi while (ESC_IS_LO) { if (cmp32(micros(), timeout_timer) > 0) goto timeout; }
#define WaitPinLo while (ESC_IS_HI) { if (timeUs_t(micros(), timeout_timer) > 0) goto timeout; }
#define WaitPinHi while (ESC_IS_LO) { if (timeUs_t(micros(), timeout_timer) > 0) goto timeout; }
static uint32_t lastBitTime;
static timeUs_t lastBitTime;
static uint32_t hiLoTsh;
static uint8_t SeqNumber;
@ -141,7 +141,7 @@ static void StkSendPacketFooter(void)
static int8_t ReadBit(void)
{
uint32_t btimer = micros();
timeUs_t btimer = micros();
uint32_t timeout_timer = btimer + STK_BIT_TIMEOUT;
WaitPinLo;
WaitPinHi;

View file

@ -69,15 +69,15 @@ void warningLedRefresh(void)
break;
}
uint32_t now = micros();
timeUs_t now = micros();
warningLedTimer = now + 500000;
}
void warningLedUpdate(void)
{
uint32_t now = micros();
timeUs_t now = micros();
if ((int32_t)(now - warningLedTimer) < 0) {
if ((timeDelta_t)(now - warningLedTimer) < 0) {
return;
}

View file

@ -51,7 +51,7 @@ STATIC_UNIT_TESTED crsfFrame_t crsfFrame;
STATIC_UNIT_TESTED uint32_t crsfChannelData[CRSF_MAX_CHANNEL];
static serialPort_t *serialPort;
static uint32_t crsfFrameStartAt = 0;
static timeUs_t crsfFrameStartAt = 0;
static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
static uint8_t telemetryBufLen = 0;
@ -124,7 +124,7 @@ typedef struct crsfPayloadLinkStatistics_s crsfPayloadLinkStatistics_t;
STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c)
{
static uint8_t crsfFramePosition = 0;
const uint32_t now = micros();
const timeUs_t now = micros();
#ifdef DEBUG_CRSF_PACKETS
debug[2] = now - crsfFrameStartAt;
@ -238,7 +238,7 @@ void crsfRxSendTelemetryData(void)
// check that we are not in bi dir mode or that we are not currently receiving data (ie in the middle of an RX frame)
// and that there is time to send the telemetry frame before the next RX frame arrives
if (CRSF_PORT_OPTIONS & SERIAL_BIDIR) {
const uint32_t timeSinceStartOfFrame = micros() - crsfFrameStartAt;
const timeDelta_t timeSinceStartOfFrame = micros() - crsfFrameStartAt;
if ((timeSinceStartOfFrame < CRSF_TIME_NEEDED_PER_FRAME_US) ||
(timeSinceStartOfFrame > CRSF_TIME_BETWEEN_FRAMES_US - CRSF_TIME_NEEDED_PER_FRAME_US)) {
return;

View file

@ -56,13 +56,13 @@ static uint8_t ibus[IBUS_BUFFSIZE] = { 0, };
// Receive ISR callback
static void ibusDataReceive(uint16_t c)
{
uint32_t ibusTime;
static uint32_t ibusTimeLast;
timeUs_t ibusTime;
static timeUs_t ibusTimeLast;
static uint8_t ibusFramePosition;
ibusTime = micros();
if ((ibusTime - ibusTimeLast) > 3000)
if ((timeDelta_t)(ibusTime - ibusTimeLast) > 3000)
ibusFramePosition = 0;
ibusTimeLast = ibusTime;

View file

@ -296,9 +296,9 @@ void jetiExBusFrameReset()
// Receive ISR callback
static void jetiExBusDataReceive(uint16_t c)
{
uint32_t now;
static uint32_t jetiExBusTimeLast = 0;
static int32_t jetiExBusTimeInterval;
timeUs_t now;
static timeUs_t jetiExBusTimeLast = 0;
static timeDelta_t jetiExBusTimeInterval;
static uint8_t *jetiExBusFrame;

View file

@ -200,8 +200,8 @@ rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload)
{
static uint8_t ackCount;
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
int totalDelayUs;
uint32_t timeNowUs;
timeDelta_t totalDelayUs;
timeUs_t timeNowUs;
switch (protocolState) {
case STATE_BIND:

View file

@ -100,8 +100,8 @@ STATIC_UNIT_TESTED uint8_t h8_3dRfChannels[H8_3D_RF_CHANNEL_COUNT];
#define DATA_HOP_TIMEOUT 5000 // 5ms
#define BIND_HOP_TIMEOUT 1000 // 1ms, to find the bind channel as quickly as possible
static uint32_t hopTimeout = BIND_HOP_TIMEOUT;
static uint32_t timeOfLastHop;
static timeUs_t hopTimeout = BIND_HOP_TIMEOUT;
static timeUs_t timeOfLastHop;
STATIC_UNIT_TESTED bool h8_3dCheckBindPacket(const uint8_t *payload)
{
@ -244,7 +244,7 @@ rx_spi_received_e h8_3dNrf24DataReceived(uint8_t *payload)
}
break;
}
const uint32_t timeNowUs = micros();
const timeUs_t timeNowUs = micros();
if ((ret == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
h8_3dHopToNextChannel();
timeOfLastHop = timeNowUs;

View file

@ -147,8 +147,8 @@ STATIC_UNIT_TESTED uint8_t inavRfChannelIndex;
STATIC_UNIT_TESTED uint8_t inavRfChannels[INAV_RF_CHANNEL_COUNT_MAX];
#define INAV_RF_BIND_CHANNEL 0x4c
static uint32_t timeOfLastHop;
static const uint32_t hopTimeout = 5000; // 5ms
static timeUs_t timeOfLastHop;
static const timeUs_t hopTimeout = 5000; // 5ms
static void whitenPayload(uint8_t *payload, uint8_t len)
{
@ -364,7 +364,7 @@ static void writeBindAckPayload(uint8_t *payload)
rx_spi_received_e inavNrf24DataReceived(uint8_t *payload)
{
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
uint32_t timeNowUs;
timeUs_t timeNowUs;
switch (protocolState) {
case STATE_BIND:
if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize)) {

View file

@ -118,8 +118,8 @@ STATIC_UNIT_TESTED uint8_t symaRfChannels[SYMA_X5C_RF_BIND_CHANNEL_COUNT] = {0x
STATIC_UNIT_TESTED const uint8_t symaRfChannelsX5C[SYMA_X5C_RF_CHANNEL_COUNT] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24, 0x27, 0x2c, 0x1c, 0x3e, 0x39, 0x2d, 0x22};
static uint32_t packetCount = 0;
static uint32_t timeOfLastHop;
static uint32_t hopTimeout = 10000; // 10ms
static timeUs_t timeOfLastHop;
static timeUs_t hopTimeout = 10000; // 10ms
STATIC_UNIT_TESTED bool symaCheckBindPacket(const uint8_t *packet)
{

View file

@ -97,9 +97,9 @@ static const uint8_t v2x2_freq_hopping[][V2X2_NFREQCHANNELS] = {
STATIC_UNIT_TESTED uint8_t rf_channels[V2X2_NFREQCHANNELS];
STATIC_UNIT_TESTED uint8_t rf_ch_num;
STATIC_UNIT_TESTED uint8_t bind_phase;
static uint32_t packet_timer;
static timeUs_t packet_timer;
STATIC_UNIT_TESTED uint8_t txid[TXIDSIZE];
static uint32_t rx_timeout;
static timeUs_t rx_timeout;
extern uint16_t rxSpiRcData[];
static const unsigned char v2x2_channelindex[] = {RC_SPI_THROTTLE,RC_SPI_YAW,RC_SPI_PITCH,RC_SPI_ROLL,
@ -197,7 +197,7 @@ void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
static rx_spi_received_e readrx(uint8_t *packet)
{
if (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_STATUS_RX_DR))) {
uint32_t t = micros() - packet_timer;
timeDelta_t t = micros() - packet_timer;
if (t > rx_timeout) {
switch_channel();
packet_timer = micros();

View file

@ -76,7 +76,7 @@ static bool rxIsInFailsafeModeNotDataDriven = true;
static timeUs_t rxUpdateAt = 0;
static timeUs_t needRxSignalBefore = 0;
static timeUs_t needRxSignalMaxDelayUs = 0;
static timeDelta_t needRxSignalMaxDelayUs = 0;
static timeUs_t suspendRxSignalUntil = 0;
static uint8_t skipRxSamples = 0;

View file

@ -121,9 +121,9 @@ static void sbusDataReceive(uint16_t c)
{
static uint8_t sbusFramePosition = 0;
static uint32_t sbusFrameStartAt = 0;
uint32_t now = micros();
timeUs_t now = micros();
int32_t sbusFrameTime = now - sbusFrameStartAt;
timeDelta_t sbusFrameTime = now - sbusFrameStartAt;
if (sbusFrameTime > (long)(SBUS_TIME_NEEDED_PER_FRAME + 500)) {
sbusFramePosition = 0;

View file

@ -73,8 +73,9 @@ static IO_t BindPlug = DEFIO_IO(NONE);
// Receive ISR callback
static void spektrumDataReceive(uint16_t c)
{
uint32_t spekTime, spekTimeInterval;
static uint32_t spekTimeLast = 0;
timeUs_t spekTime;
timeDelta_t spekTimeInterval;
static timeUs_t spekTimeLast = 0;
static uint8_t spekFramePosition = 0;
spekTime = micros();

View file

@ -70,12 +70,12 @@ static uint8_t sumdChannelCount;
// Receive ISR callback
static void sumdDataReceive(uint16_t c)
{
uint32_t sumdTime;
static uint32_t sumdTimeLast;
timeUs_t sumdTime;
static timeUs_t sumdTimeLast;
static uint8_t sumdIndex;
sumdTime = micros();
if ((sumdTime - sumdTimeLast) > 4000)
if ((timeDelta_t)(sumdTime - sumdTimeLast) > 4000)
sumdIndex = 0;
sumdTimeLast = sumdTime;

View file

@ -57,8 +57,9 @@ static serialPort_t *sumhPort;
// Receive ISR callback
static void sumhDataReceive(uint16_t c)
{
uint32_t sumhTime;
static uint32_t sumhTimeLast, sumhTimeInterval;
timeUs_t sumhTime;
timeDelta_t sumhTimeInterval;
static timeUs_t sumhTimeLast;
static uint8_t sumhFramePosition;
sumhTime = micros();

View file

@ -208,12 +208,13 @@ static void xBusUnpackRJ01Frame(void)
// Receive ISR callback
static void xBusDataReceive(uint16_t c)
{
uint32_t now;
static uint32_t xBusTimeLast, xBusTimeInterval;
timeUs_t now;
static timeUs_t xBusTimeLast;
timeDelta_t xBusTimeInterval;
// Check if we shall reset frame position due to time
now = micros();
xBusTimeInterval = now - xBusTimeLast;
xBusTimeInterval = (timeDelta_t)(now - xBusTimeLast);
xBusTimeLast = now;
if (xBusTimeInterval > XBUS_MAX_FRAME_TIME) {
xBusFramePosition = 0;

View file

@ -38,7 +38,7 @@ static cfTask_t *currentTask = NULL;
static uint32_t totalWaitingTasks;
static uint32_t totalWaitingTasksSamples;
static timeUs_t realtimeGuardInterval;
static timeDelta_t realtimeGuardInterval;
uint16_t averageSystemLoadPercent = 0;
@ -136,10 +136,10 @@ void taskSystem(timeUs_t currentTimeUs)
}
// Calculate guard interval
timeUs_t maxNonRealtimeTaskTime = 0;
timeDelta_t maxNonRealtimeTaskTime = 0;
for (const cfTask_t *task = queueFirst(); task != NULL; task = queueNext()) {
if (task->staticPriority != TASK_PRIORITY_REALTIME) {
const timeUs_t taskAverageExecutionTime = task->movingSumExecutionTime / TASK_MOVING_SUM_COUNT;
const timeDelta_t taskAverageExecutionTime = task->movingSumExecutionTime / TASK_MOVING_SUM_COUNT;
maxNonRealtimeTaskTime = MAX(maxNonRealtimeTaskTime, taskAverageExecutionTime);
}
}
@ -195,7 +195,7 @@ void setTaskEnabled(cfTaskId_e taskId, bool enabled)
}
}
timeUs_t getTaskDeltaTime(cfTaskId_e taskId)
timeDelta_t getTaskDeltaTime(cfTaskId_e taskId)
{
if (taskId == TASK_SELF || taskId < TASK_COUNT) {
cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId];
@ -217,13 +217,13 @@ void scheduler(void)
const timeUs_t currentTimeUs = micros();
// Check for realtime tasks
timeUs_t timeToNextRealtimeTask = TIMEUS_MAX;
timeDelta_t timeToNextRealtimeTask = UINT32_MAX;
for (const cfTask_t *task = queueFirst(); task != NULL && task->staticPriority >= TASK_PRIORITY_REALTIME; task = queueNext()) {
const timeUs_t nextExecuteAt = task->lastExecutedAt + task->desiredPeriod;
if ((int32_t)(currentTimeUs - nextExecuteAt) >= 0) {
if ((timeDelta_t)(currentTimeUs - nextExecuteAt) >= 0) {
timeToNextRealtimeTask = 0;
} else {
const timeUs_t newTimeInterval = nextExecuteAt - currentTimeUs;
const timeDelta_t newTimeInterval = (timeDelta_t)(nextExecuteAt - currentTimeUs);
timeToNextRealtimeTask = MIN(timeToNextRealtimeTask, newTimeInterval);
}
}
@ -288,14 +288,14 @@ void scheduler(void)
if (selectedTask != NULL) {
// Found a task that should be run
selectedTask->taskLatestDeltaTime = currentTimeUs - selectedTask->lastExecutedAt;
selectedTask->taskLatestDeltaTime = (timeDelta_t)(currentTimeUs - selectedTask->lastExecutedAt);
selectedTask->lastExecutedAt = currentTimeUs;
selectedTask->dynamicPriority = 0;
// Execute task
const timeUs_t currentTimeBeforeTaskCall = micros();
selectedTask->taskFunc(currentTimeBeforeTaskCall);
const timeUs_t taskExecutionTime = micros() - currentTimeBeforeTaskCall;
const timeDelta_t taskExecutionTime = (timeDelta_t)(micros() - currentTimeBeforeTaskCall);
selectedTask->movingSumExecutionTime += taskExecutionTime - selectedTask->movingSumExecutionTime / TASK_MOVING_SUM_COUNT;

View file

@ -34,11 +34,11 @@ typedef struct {
const char * taskName;
bool isEnabled;
uint8_t staticPriority;
timeUs_t desiredPeriod;
timeUs_t maxExecutionTime;
timeDelta_t desiredPeriod;
timeDelta_t maxExecutionTime;
timeUs_t totalExecutionTime;
timeUs_t averageExecutionTime;
timeUs_t latestDeltaTime;
timeDelta_t averageExecutionTime;
timeDelta_t latestDeltaTime;
} cfTaskInfo_t;
typedef enum {
@ -102,17 +102,17 @@ typedef enum {
} cfTaskId_e;
typedef struct {
timeUs_t maxExecutionTime;
timeUs_t totalExecutionTime;
timeUs_t averageExecutionTime;
timeUs_t totalExecutionTime;
timeDelta_t maxExecutionTime;
timeDelta_t averageExecutionTime;
} cfCheckFuncInfo_t;
typedef struct {
/* Configuration */
const char * taskName;
bool (*checkFunc)(timeUs_t currentTimeUs, timeUs_t currentDeltaTime);
bool (*checkFunc)(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime);
void (*taskFunc)(timeUs_t currentTimeUs);
timeUs_t desiredPeriod; // target period of execution
timeDelta_t desiredPeriod; // target period of execution
const uint8_t staticPriority; // dynamicPriority grows in steps of this size, shouldn't be zero
/* Scheduling */
@ -120,12 +120,12 @@ typedef struct {
uint16_t taskAgeCycles;
timeUs_t lastExecutedAt; // last time of invocation
timeUs_t lastSignaledAt; // time of invocation event for event-driven tasks
timeUs_t taskLatestDeltaTime;
timeDelta_t taskLatestDeltaTime;
/* Statistics */
timeUs_t movingSumExecutionTime; // moving sum over 32 samples
timeDelta_t movingSumExecutionTime; // moving sum over 32 samples
#ifndef SKIP_TASK_STATISTICS
timeUs_t maxExecutionTime;
timeDelta_t maxExecutionTime;
timeUs_t totalExecutionTime; // total time consumed by task since boot
#endif
} cfTask_t;
@ -138,7 +138,7 @@ void getCheckFuncInfo(cfCheckFuncInfo_t *checkFuncInfo);
void getTaskInfo(cfTaskId_e taskId, cfTaskInfo_t *taskInfo);
void rescheduleTask(cfTaskId_e taskId, timeUs_t newPeriodMicros);
void setTaskEnabled(cfTaskId_e taskId, bool newEnabledState);
timeUs_t getTaskDeltaTime(cfTaskId_e taskId);
timeDelta_t getTaskDeltaTime(cfTaskId_e taskId);
void schedulerInit(void);
void scheduler(void);