1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 12:55:19 +03:00

Converted currentTime to currentTimeUs

This commit is contained in:
Martin Budden 2016-12-01 18:57:20 +00:00
parent ec0b52aea1
commit 8d3c825646
38 changed files with 197 additions and 165 deletions

View file

@ -938,7 +938,7 @@ static void writeGPSHomeFrame()
gpsHistory.GPS_home[1] = GPS_home[1]; gpsHistory.GPS_home[1] = GPS_home[1];
} }
static void writeGPSFrame(uint32_t currentTime) static void writeGPSFrame(timeUs_t currentTimeUs)
{ {
blackboxWrite('G'); blackboxWrite('G');
@ -950,7 +950,7 @@ static void writeGPSFrame(uint32_t currentTime)
*/ */
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME)) { if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME)) {
// Predict the time of the last frame in the main log // Predict the time of the last frame in the main log
blackboxWriteUnsignedVB(currentTime - blackboxHistory[1]->time); blackboxWriteUnsignedVB(currentTimeUs - blackboxHistory[1]->time);
} }
blackboxWriteUnsignedVB(GPS_numSat); blackboxWriteUnsignedVB(GPS_numSat);
@ -969,12 +969,12 @@ static void writeGPSFrame(uint32_t currentTime)
/** /**
* Fill the current state of the blackbox using values read from the flight controller * Fill the current state of the blackbox using values read from the flight controller
*/ */
static void loadMainState(uint32_t currentTime) static void loadMainState(timeUs_t currentTimeUs)
{ {
blackboxMainState_t *blackboxCurrent = blackboxHistory[0]; blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
int i; int i;
blackboxCurrent->time = currentTime; blackboxCurrent->time = currentTimeUs;
for (i = 0; i < XYZ_AXIS_COUNT; i++) { for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->axisPID_P[i] = axisPID_P[i]; blackboxCurrent->axisPID_P[i] = axisPID_P[i];
@ -1401,7 +1401,7 @@ static void blackboxAdvanceIterationTimers()
} }
// Called once every FC loop in order to log the current state // Called once every FC loop in order to log the current state
static void blackboxLogIteration(uint32_t currentTime) static void blackboxLogIteration(timeUs_t currentTimeUs)
{ {
// Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames // Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
if (blackboxShouldLogIFrame()) { if (blackboxShouldLogIFrame()) {
@ -1411,7 +1411,7 @@ static void blackboxLogIteration(uint32_t currentTime)
*/ */
writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes()); writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
loadMainState(currentTime); loadMainState(currentTimeUs);
writeIntraframe(); writeIntraframe();
} else { } else {
blackboxCheckAndLogArmingBeep(); blackboxCheckAndLogArmingBeep();
@ -1424,7 +1424,7 @@ static void blackboxLogIteration(uint32_t currentTime)
*/ */
writeSlowFrameIfNeeded(true); writeSlowFrameIfNeeded(true);
loadMainState(currentTime); loadMainState(currentTimeUs);
writeInterframe(); writeInterframe();
} }
#ifdef GPS #ifdef GPS
@ -1440,11 +1440,11 @@ static void blackboxLogIteration(uint32_t currentTime)
|| (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) { || (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
writeGPSHomeFrame(); writeGPSHomeFrame();
writeGPSFrame(currentTime); writeGPSFrame(currentTimeUs);
} else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0] } else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0]
|| GPS_coord[1] != gpsHistory.GPS_coord[1]) { || GPS_coord[1] != gpsHistory.GPS_coord[1]) {
//We could check for velocity changes as well but I doubt it changes independent of position //We could check for velocity changes as well but I doubt it changes independent of position
writeGPSFrame(currentTime); writeGPSFrame(currentTimeUs);
} }
} }
#endif #endif
@ -1457,7 +1457,7 @@ static void blackboxLogIteration(uint32_t currentTime)
/** /**
* Call each flight loop iteration to perform blackbox logging. * Call each flight loop iteration to perform blackbox logging.
*/ */
void handleBlackbox(uint32_t currentTime) void handleBlackbox(timeUs_t currentTimeUs)
{ {
int i; int i;
@ -1549,12 +1549,12 @@ void handleBlackbox(uint32_t currentTime)
flightLogEvent_loggingResume_t resume; flightLogEvent_loggingResume_t resume;
resume.logIteration = blackboxIteration; resume.logIteration = blackboxIteration;
resume.currentTime = currentTime; resume.currentTime = currentTimeUs;
blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume); blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
blackboxSetState(BLACKBOX_STATE_RUNNING); blackboxSetState(BLACKBOX_STATE_RUNNING);
blackboxLogIteration(currentTime); blackboxLogIteration(currentTimeUs);
} }
// Keep the logging timers ticking so our log iteration continues to advance // Keep the logging timers ticking so our log iteration continues to advance
@ -1566,7 +1566,7 @@ void handleBlackbox(uint32_t currentTime)
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX) && !startedLoggingInTestMode) { if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX) && !startedLoggingInTestMode) {
blackboxSetState(BLACKBOX_STATE_PAUSED); blackboxSetState(BLACKBOX_STATE_PAUSED);
} else { } else {
blackboxLogIteration(currentTime); blackboxLogIteration(currentTimeUs);
} }
blackboxAdvanceIterationTimers(); blackboxAdvanceIterationTimers();

View file

@ -19,6 +19,8 @@
#include "blackbox/blackbox_fielddefs.h" #include "blackbox/blackbox_fielddefs.h"
#include "common/time.h"
typedef struct blackboxConfig_s { typedef struct blackboxConfig_s {
uint8_t rate_num; uint8_t rate_num;
uint8_t rate_denom; uint8_t rate_denom;
@ -29,7 +31,7 @@ typedef struct blackboxConfig_s {
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data); void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
void initBlackbox(void); void initBlackbox(void);
void handleBlackbox(uint32_t currentTime); void handleBlackbox(timeUs_t currentTimeUs);
void startBlackbox(void); void startBlackbox(void);
void finishBlackbox(void); void finishBlackbox(void);

View file

@ -897,16 +897,16 @@ static void cmsUpdate(uint32_t currentTimeUs)
lastCalledMs = currentTimeMs; lastCalledMs = currentTimeMs;
} }
void cmsHandler(uint32_t currentTime) void cmsHandler(timeUs_t currentTimeUs)
{ {
if (cmsDeviceCount < 0) if (cmsDeviceCount < 0)
return; return;
static uint32_t lastCalled = 0; static timeUs_t lastCalledUs = 0;
if (currentTime >= lastCalled + CMS_UPDATE_INTERVAL_US) { if (currentTimeUs >= lastCalledUs + CMS_UPDATE_INTERVAL_US) {
lastCalled = currentTime; lastCalledUs = currentTimeUs;
cmsUpdate(currentTime); cmsUpdate(currentTimeUs);
} }
} }

View file

@ -2,12 +2,14 @@
#include "drivers/display.h" #include "drivers/display.h"
#include "common/time.h"
// Device management // Device management
bool cmsDisplayPortRegister(displayPort_t *pDisplay); bool cmsDisplayPortRegister(displayPort_t *pDisplay);
// For main.c and scheduler // For main.c and scheduler
void cmsInit(void); void cmsInit(void);
void cmsHandler(uint32_t currentTime); void cmsHandler(timeUs_t currentTimeUs);
long cmsMenuChange(displayPort_t *pPort, const void *ptr); long cmsMenuChange(displayPort_t *pPort, const void *ptr);
long cmsMenuExit(displayPort_t *pPort, const void *ptr); long cmsMenuExit(displayPort_t *pPort, const void *ptr);

View file

@ -21,6 +21,8 @@
#include "platform.h" #include "platform.h"
// time difference, 32 bits always sufficient
typedef int32_t timeDelta_t;
// millisecond time // millisecond time
typedef uint32_t timeMs_t ; typedef uint32_t timeMs_t ;
// microsecond time // microsecond time
@ -31,3 +33,5 @@ typedef uint64_t timeUs_t;
typedef uint32_t timeUs_t; typedef uint32_t timeUs_t;
#define TIMEUS_MAX UINT32_MAX #define TIMEUS_MAX UINT32_MAX
#endif #endif
static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }

View file

@ -74,7 +74,7 @@
#include "config/config_master.h" #include "config/config_master.h"
#ifdef USE_BST #ifdef USE_BST
void taskBstMasterProcess(uint32_t currentTime); void taskBstMasterProcess(timeUs_t currentTimeUs);
#endif #endif
#define TASK_PERIOD_HZ(hz) (1000000 / (hz)) #define TASK_PERIOD_HZ(hz) (1000000 / (hz))
@ -87,16 +87,16 @@ void taskBstMasterProcess(uint32_t currentTime);
#define IBATINTERVAL (6 * 3500) #define IBATINTERVAL (6 * 3500)
static void taskUpdateAccelerometer(uint32_t currentTime) static void taskUpdateAccelerometer(timeUs_t currentTimeUs)
{ {
UNUSED(currentTime); UNUSED(currentTimeUs);
imuUpdateAccelerometer(&masterConfig.accelerometerTrims); imuUpdateAccelerometer(&masterConfig.accelerometerTrims);
} }
static void taskHandleSerial(uint32_t currentTime) static void taskHandleSerial(timeUs_t currentTimeUs)
{ {
UNUSED(currentTime); UNUSED(currentTimeUs);
#ifdef USE_CLI #ifdef USE_CLI
// in cli mode, all serial stuff goes to here. enter cli mode by sending # // in cli mode, all serial stuff goes to here. enter cli mode by sending #
if (cliMode) { if (cliMode) {
@ -107,13 +107,13 @@ static void taskHandleSerial(uint32_t currentTime)
mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand); mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand);
} }
static void taskUpdateBattery(uint32_t currentTime) static void taskUpdateBattery(timeUs_t currentTimeUs)
{ {
#ifdef USE_ADC #ifdef USE_ADC
static uint32_t vbatLastServiced = 0; static uint32_t vbatLastServiced = 0;
if (feature(FEATURE_VBAT) || feature(FEATURE_ESC_TELEMETRY)) { if (feature(FEATURE_VBAT) || feature(FEATURE_ESC_TELEMETRY)) {
if (cmp32(currentTime, vbatLastServiced) >= VBATINTERVAL) { if (cmp32(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
vbatLastServiced = currentTime; vbatLastServiced = currentTimeUs;
updateBattery(); updateBattery();
} }
} }
@ -121,18 +121,18 @@ static void taskUpdateBattery(uint32_t currentTime)
static uint32_t ibatLastServiced = 0; static uint32_t ibatLastServiced = 0;
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_TELEMETRY)) { if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_TELEMETRY)) {
const int32_t ibatTimeSinceLastServiced = cmp32(currentTime, ibatLastServiced); const int32_t ibatTimeSinceLastServiced = cmp32(currentTimeUs, ibatLastServiced);
if (ibatTimeSinceLastServiced >= IBATINTERVAL) { if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
ibatLastServiced = currentTime; ibatLastServiced = currentTimeUs;
updateCurrentMeter(ibatTimeSinceLastServiced, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle); updateCurrentMeter(ibatTimeSinceLastServiced, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
} }
} }
} }
static void taskUpdateRxMain(uint32_t currentTime) static void taskUpdateRxMain(timeUs_t currentTimeUs)
{ {
processRx(currentTime); processRx(currentTimeUs);
isRXDataNew = true; isRXDataNew = true;
#if !defined(BARO) && !defined(SONAR) #if !defined(BARO) && !defined(SONAR)
@ -155,18 +155,18 @@ static void taskUpdateRxMain(uint32_t currentTime)
} }
#ifdef MAG #ifdef MAG
static void taskUpdateCompass(uint32_t currentTime) static void taskUpdateCompass(timeUs_t currentTimeUs)
{ {
if (sensors(SENSOR_MAG)) { if (sensors(SENSOR_MAG)) {
compassUpdate(currentTime, &sensorTrims()->magZero); compassUpdate(currentTimeUs, &sensorTrims()->magZero);
} }
} }
#endif #endif
#ifdef BARO #ifdef BARO
static void taskUpdateBaro(uint32_t currentTime) static void taskUpdateBaro(timeUs_t currentTimeUs)
{ {
UNUSED(currentTime); UNUSED(currentTimeUs);
if (sensors(SENSOR_BARO)) { if (sensors(SENSOR_BARO)) {
const uint32_t newDeadline = baroUpdate(); const uint32_t newDeadline = baroUpdate();
@ -178,7 +178,7 @@ static void taskUpdateBaro(uint32_t currentTime)
#endif #endif
#if defined(BARO) || defined(SONAR) #if defined(BARO) || defined(SONAR)
static void taskCalculateAltitude(uint32_t currentTime) static void taskCalculateAltitude(timeUs_t currentTimeUs)
{ {
if (false if (false
#if defined(BARO) #if defined(BARO)
@ -188,26 +188,26 @@ static void taskCalculateAltitude(uint32_t currentTime)
|| sensors(SENSOR_SONAR) || sensors(SENSOR_SONAR)
#endif #endif
) { ) {
calculateEstimatedAltitude(currentTime); calculateEstimatedAltitude(currentTimeUs);
}} }}
#endif #endif
#ifdef TELEMETRY #ifdef TELEMETRY
static void taskTelemetry(uint32_t currentTime) static void taskTelemetry(timeUs_t currentTimeUs)
{ {
telemetryCheckState(); telemetryCheckState();
if (!cliMode && feature(FEATURE_TELEMETRY)) { if (!cliMode && feature(FEATURE_TELEMETRY)) {
telemetryProcess(currentTime, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle); telemetryProcess(currentTimeUs, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
} }
} }
#endif #endif
#ifdef USE_ESC_TELEMETRY #ifdef USE_ESC_TELEMETRY
static void taskEscTelemetry(uint32_t currentTime) static void taskEscTelemetry(timeUs_t currentTimeUs)
{ {
if (feature(FEATURE_ESC_TELEMETRY)) { if (feature(FEATURE_ESC_TELEMETRY)) {
escTelemetryProcess(currentTime); escTelemetryProcess(currentTimeUs);
} }
} }
#endif #endif

View file

@ -493,12 +493,12 @@ void updateMagHold(void)
magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
} }
void processRx(uint32_t currentTime) void processRx(timeUs_t currentTimeUs)
{ {
static bool armedBeeperOn = false; static bool armedBeeperOn = false;
static bool airmodeIsActivated; static bool airmodeIsActivated;
calculateRxChannelsAndUpdateFailsafe(currentTime); calculateRxChannelsAndUpdateFailsafe(currentTimeUs);
// in 3D mode, we need to be able to disarm by switch at any time // in 3D mode, we need to be able to disarm by switch at any time
if (feature(FEATURE_3D)) { if (feature(FEATURE_3D)) {
@ -506,11 +506,11 @@ void processRx(uint32_t currentTime)
mwDisarm(); mwDisarm();
} }
updateRSSI(currentTime); updateRSSI(currentTimeUs);
if (feature(FEATURE_FAILSAFE)) { if (feature(FEATURE_FAILSAFE)) {
if (currentTime > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) { if (currentTimeUs > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) {
failsafeStartMonitoring(); failsafeStartMonitoring();
} }
@ -811,9 +811,9 @@ uint8_t setPidUpdateCountDown(void)
} }
// Function for loop trigger // Function for loop trigger
void taskMainPidLoop(uint32_t currentTime) void taskMainPidLoop(timeUs_t currentTimeUs)
{ {
UNUSED(currentTime); UNUSED(currentTimeUs);
static bool runTaskMainSubprocesses; static bool runTaskMainSubprocesses;
static uint8_t pidUpdateCountdown; static uint8_t pidUpdateCountdown;

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#include "common/time.h"
extern int16_t magHold; extern int16_t magHold;
extern bool isRXDataNew; extern bool isRXDataNew;
@ -27,8 +29,8 @@ void handleInflightCalibrationStickPosition();
void mwDisarm(void); void mwDisarm(void);
void mwArm(void); void mwArm(void);
void processRx(uint32_t currentTime); void processRx(timeUs_t currentTimeUs);
void updateLEDs(void); void updateLEDs(void);
void updateRcCommands(void); void updateRcCommands(void);
void taskMainPidLoop(uint32_t currentTime); void taskMainPidLoop(timeUs_t currentTimeUs);

View file

@ -204,9 +204,9 @@ int32_t calculateAltHoldThrottleAdjustment(int32_t vel_tmp, float accZ_tmp, floa
return result; return result;
} }
void calculateEstimatedAltitude(uint32_t currentTime) void calculateEstimatedAltitude(timeUs_t currentTimeUs)
{ {
static uint32_t previousTime; static timeUs_t previousTimeUs;
uint32_t dTime; uint32_t dTime;
int32_t baroVel; int32_t baroVel;
float dt; float dt;
@ -224,11 +224,11 @@ void calculateEstimatedAltitude(uint32_t currentTime)
float sonarTransition; float sonarTransition;
#endif #endif
dTime = currentTime - previousTime; dTime = currentTimeUs - previousTimeUs;
if (dTime < BARO_UPDATE_FREQUENCY_40HZ) if (dTime < BARO_UPDATE_FREQUENCY_40HZ)
return; return;
previousTime = currentTime; previousTimeUs = currentTimeUs;
#ifdef BARO #ifdef BARO
if (!isBaroCalibrationComplete()) { if (!isBaroCalibrationComplete()) {

View file

@ -20,7 +20,7 @@
extern int32_t AltHold; extern int32_t AltHold;
extern int32_t vario; extern int32_t vario;
void calculateEstimatedAltitude(uint32_t currentTime); void calculateEstimatedAltitude(timeUs_t currentTimeUs);
struct pidProfile_s; struct pidProfile_s;
struct barometerConfig_s; struct barometerConfig_s;

View file

@ -369,7 +369,7 @@ static bool isMagnetometerHealthy(void)
return (mag.magADC[X] != 0) && (mag.magADC[Y] != 0) && (mag.magADC[Z] != 0); return (mag.magADC[X] != 0) && (mag.magADC[Y] != 0) && (mag.magADC[Z] != 0);
} }
static void imuCalculateEstimatedAttitude(uint32_t currentTime) static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
{ {
static uint32_t previousIMUUpdateTime; static uint32_t previousIMUUpdateTime;
float rawYawError = 0; float rawYawError = 0;
@ -377,8 +377,8 @@ static void imuCalculateEstimatedAttitude(uint32_t currentTime)
bool useMag = false; bool useMag = false;
bool useYaw = false; bool useYaw = false;
uint32_t deltaT = currentTime - previousIMUUpdateTime; uint32_t deltaT = currentTimeUs - previousIMUUpdateTime;
previousIMUUpdateTime = currentTime; previousIMUUpdateTime = currentTimeUs;
if (imuIsAccelerometerHealthy()) { if (imuIsAccelerometerHealthy()) {
useAcc = true; useAcc = true;
@ -414,10 +414,10 @@ void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims)
} }
} }
void imuUpdateAttitude(uint32_t currentTime) void imuUpdateAttitude(timeUs_t currentTimeUs)
{ {
if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) { if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) {
imuCalculateEstimatedAttitude(currentTime); imuCalculateEstimatedAttitude(currentTimeUs);
} else { } else {
acc.accSmooth[X] = 0; acc.accSmooth[X] = 0;
acc.accSmooth[Y] = 0; acc.accSmooth[Y] = 0;

View file

@ -19,6 +19,7 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/time.h"
#include "sensors/acceleration.h" #include "sensors/acceleration.h"
@ -96,10 +97,10 @@ void imuConfigure(
); );
float getCosTiltAngle(void); float getCosTiltAngle(void);
void calculateEstimatedAltitude(uint32_t currentTime); void calculateEstimatedAltitude(timeUs_t currentTimeUs);
union rollAndPitchTrims_u; union rollAndPitchTrims_u;
void imuUpdateAccelerometer(union rollAndPitchTrims_u *accelerometerTrims); void imuUpdateAccelerometer(union rollAndPitchTrims_u *accelerometerTrims);
void imuUpdateAttitude(uint32_t currentTime); void imuUpdateAttitude(timeUs_t currentTimeUs);
float calculateThrottleAngleScale(uint16_t throttle_correction_angle); float calculateThrottleAngleScale(uint16_t throttle_correction_angle);
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value); int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value);
float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_hz); float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_hz);

View file

@ -26,8 +26,9 @@
#include "build/debug.h" #include "build/debug.h"
#include "common/maths.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h"
#include "common/time.h"
#include "drivers/system.h" #include "drivers/system.h"

View file

@ -135,7 +135,7 @@ static uint32_t beeperNextToggleTime = 0;
// Time of last arming beep in microseconds (for blackbox) // Time of last arming beep in microseconds (for blackbox)
static uint32_t armingBeepTimeMicros = 0; static uint32_t armingBeepTimeMicros = 0;
static void beeperProcessCommand(uint32_t currentTime); static void beeperProcessCommand(timeUs_t currentTimeUs);
typedef struct beeperTableEntry_s { typedef struct beeperTableEntry_s {
uint8_t mode; uint8_t mode;
@ -280,7 +280,7 @@ void beeperGpsStatus(void)
* Beeper handler function to be called periodically in loop. Updates beeper * Beeper handler function to be called periodically in loop. Updates beeper
* state via time schedule. * state via time schedule.
*/ */
void beeperUpdate(uint32_t currentTime) void beeperUpdate(timeUs_t currentTimeUs)
{ {
// If beeper option from AUX switch has been selected // If beeper option from AUX switch has been selected
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) { if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) {
@ -300,7 +300,7 @@ void beeperUpdate(uint32_t currentTime)
return; return;
} }
if (beeperNextToggleTime > currentTime) { if (beeperNextToggleTime > currentTimeUs) {
return; return;
} }
@ -328,13 +328,13 @@ void beeperUpdate(uint32_t currentTime)
} }
} }
beeperProcessCommand(currentTime); beeperProcessCommand(currentTimeUs);
} }
/* /*
* Calculates array position when next to change beeper state is due. * Calculates array position when next to change beeper state is due.
*/ */
static void beeperProcessCommand(uint32_t currentTime) static void beeperProcessCommand(timeUs_t currentTimeUs)
{ {
if (currentBeeperEntry->sequence[beeperPos] == BEEPER_COMMAND_REPEAT) { if (currentBeeperEntry->sequence[beeperPos] == BEEPER_COMMAND_REPEAT) {
beeperPos = 0; beeperPos = 0;
@ -342,7 +342,7 @@ static void beeperProcessCommand(uint32_t currentTime)
beeperSilence(); beeperSilence();
} else { } else {
// Otherwise advance the sequence and calculate next toggle time // Otherwise advance the sequence and calculate next toggle time
beeperNextToggleTime = currentTime + 1000 * 10 * currentBeeperEntry->sequence[beeperPos]; beeperNextToggleTime = currentTimeUs + 1000 * 10 * currentBeeperEntry->sequence[beeperPos];
beeperPos++; beeperPos++;
} }
} }
@ -400,7 +400,7 @@ bool isBeeperOn(void)
void beeper(beeperMode_e mode) {UNUSED(mode);} void beeper(beeperMode_e mode) {UNUSED(mode);}
void beeperSilence(void) {} void beeperSilence(void) {}
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);} void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
void beeperUpdate(uint32_t currentTime) {UNUSED(currentTime);} void beeperUpdate(timeUs_t currentTimeUs) {UNUSED(currentTimeUs);}
uint32_t getArmingBeepTimeMicros(void) {return 0;} uint32_t getArmingBeepTimeMicros(void) {return 0;}
beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;}
const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;} const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;}

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#include "common/time.h"
typedef enum { typedef enum {
// IMPORTANT: these are in priority order, 0 = Highest // IMPORTANT: these are in priority order, 0 = Highest
BEEPER_SILENCE = 0, // Silence, see beeperSilence() BEEPER_SILENCE = 0, // Silence, see beeperSilence()
@ -47,7 +49,7 @@ typedef enum {
void beeper(beeperMode_e mode); void beeper(beeperMode_e mode);
void beeperSilence(void); void beeperSilence(void);
void beeperUpdate(uint32_t currentTime); void beeperUpdate(timeUs_t currentTimeUs);
void beeperConfirmationBeeps(uint8_t beepCount); void beeperConfirmationBeeps(uint8_t beepCount);
uint32_t getArmingBeepTimeMicros(void); uint32_t getArmingBeepTimeMicros(void);
beeperMode_e beeperModeForTableIndex(int idx); beeperMode_e beeperModeForTableIndex(int idx);

View file

@ -586,7 +586,7 @@ void showDebugPage(void)
} }
#endif #endif
void dashboardUpdate(uint32_t currentTime) void dashboardUpdate(timeUs_t currentTimeUs)
{ {
static uint8_t previousArmedState = 0; static uint8_t previousArmedState = 0;
@ -596,12 +596,12 @@ void dashboardUpdate(uint32_t currentTime)
} }
#endif #endif
const bool updateNow = (int32_t)(currentTime - nextDisplayUpdateAt) >= 0L; const bool updateNow = (int32_t)(currentTimeUs - nextDisplayUpdateAt) >= 0L;
if (!updateNow) { if (!updateNow) {
return; return;
} }
nextDisplayUpdateAt = currentTime + DISPLAY_UPDATE_FREQUENCY; nextDisplayUpdateAt = currentTimeUs + DISPLAY_UPDATE_FREQUENCY;
bool armedState = ARMING_FLAG(ARMED) ? true : false; bool armedState = ARMING_FLAG(ARMED) ? true : false;
bool armedStateChanged = armedState != previousArmedState; bool armedStateChanged = armedState != previousArmedState;
@ -621,7 +621,7 @@ void dashboardUpdate(uint32_t currentTime)
} }
pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) || pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) ||
(((int32_t)(currentTime - pageState.nextPageAt) >= 0L && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED))); (((int32_t)(currentTimeUs - pageState.nextPageAt) >= 0L && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)));
if (pageState.pageChanging && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)) { if (pageState.pageChanging && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)) {
pageState.cycleIndex++; pageState.cycleIndex++;
pageState.cycleIndex = pageState.cycleIndex % CYCLE_PAGE_ID_COUNT; pageState.cycleIndex = pageState.cycleIndex % CYCLE_PAGE_ID_COUNT;
@ -631,7 +631,7 @@ void dashboardUpdate(uint32_t currentTime)
if (pageState.pageChanging) { if (pageState.pageChanging) {
pageState.pageFlags &= ~PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; pageState.pageFlags &= ~PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
pageState.nextPageAt = currentTime + PAGE_CYCLE_FREQUENCY; pageState.nextPageAt = currentTimeUs + PAGE_CYCLE_FREQUENCY;
// Some OLED displays do not respond on the first initialisation so refresh the display // Some OLED displays do not respond on the first initialisation so refresh the display
// when the page changes in the hopes the hardware responds. This also allows the // when the page changes in the hopes the hardware responds. This also allows the
@ -730,7 +730,7 @@ void dashboardShowFixedPage(pageId_e pageId)
dashboardDisablePageCycling(); dashboardDisablePageCycling();
} }
void dashboardSetNextPageChangeAt(uint32_t futureMicros) void dashboardSetNextPageChangeAt(timeUs_t futureMicros)
{ {
pageState.nextPageAt = futureMicros; pageState.nextPageAt = futureMicros;
} }

View file

@ -15,6 +15,8 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "common/time.h"
#define ENABLE_DEBUG_DASHBOARD_PAGE #define ENABLE_DEBUG_DASHBOARD_PAGE
typedef enum { typedef enum {
@ -37,11 +39,11 @@ typedef enum {
struct rxConfig_s; struct rxConfig_s;
void dashboardInit(struct rxConfig_s *intialRxConfig); void dashboardInit(struct rxConfig_s *intialRxConfig);
void dashboardUpdate(uint32_t currentTime); void dashboardUpdate(timeUs_t currentTimeUs);
void dashboardShowFixedPage(pageId_e pageId); void dashboardShowFixedPage(pageId_e pageId);
void dashboardEnablePageCycling(void); void dashboardEnablePageCycling(void);
void dashboardDisablePageCycling(void); void dashboardDisablePageCycling(void);
void dashboardResetPageCycling(void); void dashboardResetPageCycling(void);
void dashboardSetNextPageChangeAt(uint32_t futureMicros); void dashboardSetNextPageChangeAt(timeUs_t futureMicros);

View file

@ -395,16 +395,16 @@ void gpsInitHardware(void)
} }
} }
static void updateGpsIndicator(uint32_t currentTime) static void updateGpsIndicator(timeUs_t currentTimeUs)
{ {
static uint32_t GPSLEDTime; static uint32_t GPSLEDTime;
if ((int32_t)(currentTime - GPSLEDTime) >= 0 && (GPS_numSat >= 5)) { if ((int32_t)(currentTimeUs - GPSLEDTime) >= 0 && (GPS_numSat >= 5)) {
GPSLEDTime = currentTime + 150000; GPSLEDTime = currentTimeUs + 150000;
LED1_TOGGLE; LED1_TOGGLE;
} }
} }
void gpsUpdate(uint32_t currentTime) void gpsUpdate(timeUs_t currentTimeUs)
{ {
// read out available GPS bytes // read out available GPS bytes
if (gpsPort) { if (gpsPort) {
@ -429,7 +429,7 @@ void gpsUpdate(uint32_t currentTime)
gpsData.baudrateIndex++; gpsData.baudrateIndex++;
gpsData.baudrateIndex %= GPS_INIT_ENTRIES; gpsData.baudrateIndex %= GPS_INIT_ENTRIES;
} }
gpsData.lastMessage = currentTime / 1000; gpsData.lastMessage = currentTimeUs / 1000;
// TODO - move some / all of these into gpsData // TODO - move some / all of these into gpsData
GPS_numSat = 0; GPS_numSat = 0;
DISABLE_STATE(GPS_FIX); DISABLE_STATE(GPS_FIX);
@ -438,7 +438,7 @@ void gpsUpdate(uint32_t currentTime)
case GPS_RECEIVING_DATA: case GPS_RECEIVING_DATA:
// check for no data/gps timeout/cable disconnection etc // check for no data/gps timeout/cable disconnection etc
if (currentTime / 1000 - gpsData.lastMessage > GPS_TIMEOUT) { if (currentTimeUs / 1000 - gpsData.lastMessage > GPS_TIMEOUT) {
// remove GPS from capability // remove GPS from capability
sensorsClear(SENSOR_GPS); sensorsClear(SENSOR_GPS);
gpsSetState(GPS_LOST_COMMUNICATION); gpsSetState(GPS_LOST_COMMUNICATION);
@ -446,7 +446,7 @@ void gpsUpdate(uint32_t currentTime)
break; break;
} }
if (sensors(SENSOR_GPS)) { if (sensors(SENSOR_GPS)) {
updateGpsIndicator(currentTime); updateGpsIndicator(currentTimeUs);
} }
} }

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#include "common/time.h"
#define LAT 0 #define LAT 0
#define LON 1 #define LON 1
@ -119,5 +121,5 @@ extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Str
struct serialConfig_s; struct serialConfig_s;
void gpsInit(struct serialConfig_s *serialConfig, gpsConfig_t *initialGpsConfig); void gpsInit(struct serialConfig_s *serialConfig, gpsConfig_t *initialGpsConfig);
void gpsUpdate(uint32_t currentTime); void gpsUpdate(timeUs_t currentTimeUs);
bool gpsNewFrame(uint8_t c); bool gpsNewFrame(uint8_t c);

View file

@ -518,7 +518,7 @@ typedef enum {
WARNING_FAILSAFE, WARNING_FAILSAFE,
} warningFlags_e; } warningFlags_e;
static void applyLedWarningLayer(bool updateNow, uint32_t *timer) static void applyLedWarningLayer(bool updateNow, timeUs_t *timer)
{ {
static uint8_t warningFlashCounter = 0; static uint8_t warningFlashCounter = 0;
static uint8_t warningFlags = 0; // non-zero during blinks static uint8_t warningFlags = 0; // non-zero during blinks
@ -564,7 +564,7 @@ static void applyLedWarningLayer(bool updateNow, uint32_t *timer)
} }
} }
static void applyLedBatteryLayer(bool updateNow, uint32_t *timer) static void applyLedBatteryLayer(bool updateNow, timeUs_t *timer)
{ {
static bool flash = false; static bool flash = false;
@ -601,7 +601,7 @@ static void applyLedBatteryLayer(bool updateNow, uint32_t *timer)
} }
} }
static void applyLedRssiLayer(bool updateNow, uint32_t *timer) static void applyLedRssiLayer(bool updateNow, timeUs_t *timer)
{ {
static bool flash = false; static bool flash = false;
@ -632,7 +632,7 @@ static void applyLedRssiLayer(bool updateNow, uint32_t *timer)
} }
#ifdef GPS #ifdef GPS
static void applyLedGpsLayer(bool updateNow, uint32_t *timer) static void applyLedGpsLayer(bool updateNow, timeUs_t *timer)
{ {
static uint8_t gpsFlashCounter = 0; static uint8_t gpsFlashCounter = 0;
static uint8_t gpsPauseCounter = 0; static uint8_t gpsPauseCounter = 0;
@ -671,7 +671,7 @@ static void applyLedGpsLayer(bool updateNow, uint32_t *timer)
#define INDICATOR_DEADBAND 25 #define INDICATOR_DEADBAND 25
static void applyLedIndicatorLayer(bool updateNow, uint32_t *timer) static void applyLedIndicatorLayer(bool updateNow, timeUs_t *timer)
{ {
static bool flash = 0; static bool flash = 0;
@ -734,7 +734,7 @@ static void updateLedRingCounts(void)
ledCounts.ringSeqLen = seqLen; ledCounts.ringSeqLen = seqLen;
} }
static void applyLedThrustRingLayer(bool updateNow, uint32_t *timer) static void applyLedThrustRingLayer(bool updateNow, timeUs_t *timer)
{ {
static uint8_t rotationPhase; static uint8_t rotationPhase;
int ledRingIndex = 0; int ledRingIndex = 0;
@ -804,7 +804,7 @@ static void larsonScannerNextStep(larsonParameters_t *larsonParameters, int delt
} }
} }
static void applyLarsonScannerLayer(bool updateNow, uint32_t *timer) static void applyLarsonScannerLayer(bool updateNow, timeUs_t *timer)
{ {
static larsonParameters_t larsonParameters = { 0, 0, 1 }; static larsonParameters_t larsonParameters = { 0, 0, 1 };
@ -829,7 +829,7 @@ static void applyLarsonScannerLayer(bool updateNow, uint32_t *timer)
} }
// blink twice, then wait ; either always or just when landing // blink twice, then wait ; either always or just when landing
static void applyLedBlinkLayer(bool updateNow, uint32_t *timer) static void applyLedBlinkLayer(bool updateNow, timeUs_t *timer)
{ {
const uint16_t blinkPattern = 0x8005; // 0b1000000000000101; const uint16_t blinkPattern = 0x8005; // 0b1000000000000101;
static uint16_t blinkMask; static uint16_t blinkMask;
@ -856,7 +856,7 @@ static void applyLedBlinkLayer(bool updateNow, uint32_t *timer)
} }
#ifdef USE_LED_ANIMATION #ifdef USE_LED_ANIMATION
static void applyLedAnimationLayer(bool updateNow, uint32_t *timer) static void applyLedAnimationLayer(bool updateNow, timeUs_t *timer)
{ {
static uint8_t frameCounter = 0; static uint8_t frameCounter = 0;
const int animationFrames = ledGridHeight; const int animationFrames = ledGridHeight;
@ -904,14 +904,14 @@ typedef enum {
timTimerCount timTimerCount
} timId_e; } timId_e;
static uint32_t timerVal[timTimerCount]; static timeUs_t timerVal[timTimerCount];
// function to apply layer. // function to apply layer.
// function must replan self using timer pointer // function must replan self using timer pointer
// when updateNow is true (timer triggered), state must be updated first, // when updateNow is true (timer triggered), state must be updated first,
// before calculating led state. Otherwise update started by different trigger // before calculating led state. Otherwise update started by different trigger
// may modify LED state. // may modify LED state.
typedef void applyLayerFn_timed(bool updateNow, uint32_t *timer); typedef void applyLayerFn_timed(bool updateNow, timeUs_t *timer);
static applyLayerFn_timed* layerTable[] = { static applyLayerFn_timed* layerTable[] = {
[timBlink] = &applyLedBlinkLayer, [timBlink] = &applyLedBlinkLayer,
@ -929,7 +929,7 @@ static applyLayerFn_timed* layerTable[] = {
[timRing] = &applyLedThrustRingLayer [timRing] = &applyLedThrustRingLayer
}; };
void ledStripUpdate(uint32_t currentTime) void ledStripUpdate(timeUs_t currentTimeUs)
{ {
if (!(ledStripInitialised && isWS2811LedStripReady())) { if (!(ledStripInitialised && isWS2811LedStripReady())) {
return; return;
@ -944,13 +944,13 @@ void ledStripUpdate(uint32_t currentTime)
} }
ledStripEnabled = true; ledStripEnabled = true;
const uint32_t now = currentTime; const uint32_t now = currentTimeUs;
// test all led timers, setting corresponding bits // test all led timers, setting corresponding bits
uint32_t timActive = 0; uint32_t timActive = 0;
for (timId_e timId = 0; timId < timTimerCount; timId++) { for (timId_e timId = 0; timId < timTimerCount; timId++) {
// sanitize timer value, so that it can be safely incremented. Handles inital timerVal value. // sanitize timer value, so that it can be safely incremented. Handles inital timerVal value.
int32_t delta = cmp32(now, timerVal[timId]); const timeDelta_t delta = cmpTimeUs(now, timerVal[timId]);
// max delay is limited to 5s // max delay is limited to 5s
if (delta < 0 && delta > -MAX_TIMER_DELAY) if (delta < 0 && delta > -MAX_TIMER_DELAY)
continue; // not ready yet continue; // not ready yet

View file

@ -18,6 +18,7 @@
#pragma once #pragma once
#include "common/color.h" #include "common/color.h"
#include "common/time.h"
#include "drivers/io_types.h" #include "drivers/io_types.h"
#define LED_MAX_STRIP_LENGTH 32 #define LED_MAX_STRIP_LENGTH 32
@ -178,7 +179,7 @@ void reevaluateLedConfig(void);
void ledStripInit(ledStripConfig_t *ledStripConfig); void ledStripInit(ledStripConfig_t *ledStripConfig);
void ledStripEnable(void); void ledStripEnable(void);
void ledStripUpdate(uint32_t currentTime); void ledStripUpdate(timeUs_t currentTimeUs);
bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex); bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex);

View file

@ -581,7 +581,7 @@ static void osdArmMotors(void)
osdResetStats(); osdResetStats();
} }
static void osdRefresh(uint32_t currentTime) static void osdRefresh(timeUs_t currentTimeUs)
{ {
static uint8_t lastSec = 0; static uint8_t lastSec = 0;
uint8_t sec; uint8_t sec;
@ -598,7 +598,7 @@ static void osdRefresh(uint32_t currentTime)
osdUpdateStats(); osdUpdateStats();
sec = currentTime / 1000000; sec = currentTimeUs / 1000000;
if (ARMING_FLAG(ARMED) && sec != lastSec) { if (ARMING_FLAG(ARMED) && sec != lastSec) {
flyTime++; flyTime++;
@ -614,7 +614,7 @@ static void osdRefresh(uint32_t currentTime)
return; return;
} }
blinkState = (currentTime / 200000) % 2; blinkState = (currentTimeUs / 200000) % 2;
#ifdef CMS #ifdef CMS
if (!displayIsGrabbed(osdDisplayPort)) { if (!displayIsGrabbed(osdDisplayPort)) {
@ -623,7 +623,7 @@ static void osdRefresh(uint32_t currentTime)
displayHeartbeat(osdDisplayPort); // heartbeat to stop Minim OSD going back into native mode displayHeartbeat(osdDisplayPort); // heartbeat to stop Minim OSD going back into native mode
#ifdef OSD_CALLS_CMS #ifdef OSD_CALLS_CMS
} else { } else {
cmsUpdate(currentTime); cmsUpdate(currentTimeUs);
#endif #endif
} }
#endif #endif
@ -632,7 +632,7 @@ static void osdRefresh(uint32_t currentTime)
/* /*
* Called periodically by the scheduler * Called periodically by the scheduler
*/ */
void osdUpdate(uint32_t currentTime) void osdUpdate(timeUs_t currentTimeUs)
{ {
static uint32_t counter = 0; static uint32_t counter = 0;
#ifdef MAX7456_DMA_CHANNEL_TX #ifdef MAX7456_DMA_CHANNEL_TX
@ -649,7 +649,7 @@ void osdUpdate(uint32_t currentTime)
#define DRAW_FREQ_DENOM 10 // MWOSD @ 115200 baud #define DRAW_FREQ_DENOM 10 // MWOSD @ 115200 baud
#endif #endif
if (counter++ % DRAW_FREQ_DENOM == 0) { if (counter++ % DRAW_FREQ_DENOM == 0) {
osdRefresh(currentTime); osdRefresh(currentTimeUs);
} else { // rest of time redraw screen 10 chars per idle so it doesn't lock the main idle } else { // rest of time redraw screen 10 chars per idle so it doesn't lock the main idle
displayDrawScreen(osdDisplayPort); displayDrawScreen(osdDisplayPort);
} }

View file

@ -64,4 +64,4 @@ struct displayPort_s;
void osdInit(struct displayPort_s *osdDisplayPort); void osdInit(struct displayPort_s *osdDisplayPort);
void osdResetConfig(osd_profile_t *osdProfile); void osdResetConfig(osd_profile_t *osdProfile);
void osdResetAlarms(void); void osdResetAlarms(void);
void osdUpdate(uint32_t currentTime); void osdUpdate(timeUs_t currentTimeUs);

View file

@ -37,12 +37,12 @@ static bool transponderInitialised = false;
static bool transponderRepeat = false; static bool transponderRepeat = false;
// timers // timers
static uint32_t nextUpdateAt = 0; static timeUs_t nextUpdateAtUs = 0;
#define JITTER_DURATION_COUNT (sizeof(jitterDurations) / sizeof(uint8_t)) #define JITTER_DURATION_COUNT (sizeof(jitterDurations) / sizeof(uint8_t))
static uint8_t jitterDurations[] = {0,9,4,8,3,9,6,7,1,6,9,7,8,2,6}; static uint8_t jitterDurations[] = {0,9,4,8,3,9,6,7,1,6,9,7,8,2,6};
void transponderUpdate(uint32_t currentTime) void transponderUpdate(timeUs_t currentTimeUs)
{ {
static uint32_t jitterIndex = 0; static uint32_t jitterIndex = 0;
@ -50,7 +50,7 @@ void transponderUpdate(uint32_t currentTime)
return; return;
} }
const bool updateNow = (int32_t)(currentTime - nextUpdateAt) >= 0L; const bool updateNow = (timeDelta_t)(currentTimeUs - nextUpdateAtUs) >= 0L;
if (!updateNow) { if (!updateNow) {
return; return;
} }
@ -61,12 +61,12 @@ void transponderUpdate(uint32_t currentTime)
jitterIndex = 0; jitterIndex = 0;
} }
nextUpdateAt = currentTime + 4500 + jitter; nextUpdateAtUs = currentTimeUs + 4500 + jitter;
#ifdef REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT #ifdef REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
// reduce current draw when USB cable is plugged in by decreasing the transponder transmit rate. // reduce current draw when USB cable is plugged in by decreasing the transponder transmit rate.
if (usbCableIsInserted()) { if (usbCableIsInserted()) {
nextUpdateAt = currentTime + (1000 * 1000) / 10; // 10 hz. nextUpdateAtUs = currentTimeUs + (1000 * 1000) / 10; // 10 hz.
} }
#endif #endif

View file

@ -17,11 +17,13 @@
#pragma once #pragma once
#include "common/time.h"
void transponderInit(uint8_t* transponderCode); void transponderInit(uint8_t* transponderCode);
void transponderEnable(void); void transponderEnable(void);
void transponderDisable(void); void transponderDisable(void);
void transponderUpdate(uint32_t currentTime); void transponderUpdate(timeUs_t currentTimeUs);
void transponderUpdateData(uint8_t* transponderData); void transponderUpdateData(uint8_t* transponderData);
void transponderTransmitOnce(void); void transponderTransmitOnce(void);
void transponderStartRepeating(void); void transponderStartRepeating(void);

View file

@ -306,12 +306,12 @@ void resumeRxSignal(void)
failsafeOnRxResume(); failsafeOnRxResume();
} }
bool rxUpdateCheck(uint32_t currentTime, uint32_t currentDeltaTime) bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
{ {
UNUSED(currentDeltaTime); UNUSED(currentDeltaTime);
if (rxSignalReceived) { if (rxSignalReceived) {
if (currentTime >= needRxSignalBefore) { if (currentTimeUs >= needRxSignalBefore) {
rxSignalReceived = false; rxSignalReceived = false;
rxSignalReceivedNotDataDriven = false; rxSignalReceivedNotDataDriven = false;
} }
@ -322,14 +322,14 @@ bool rxUpdateCheck(uint32_t currentTime, uint32_t currentDeltaTime)
if (isPPMDataBeingReceived()) { if (isPPMDataBeingReceived()) {
rxSignalReceivedNotDataDriven = true; rxSignalReceivedNotDataDriven = true;
rxIsInFailsafeModeNotDataDriven = false; rxIsInFailsafeModeNotDataDriven = false;
needRxSignalBefore = currentTime + needRxSignalMaxDelayUs; needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
resetPPMDataReceivedState(); resetPPMDataReceivedState();
} }
} else if (feature(FEATURE_RX_PARALLEL_PWM)) { } else if (feature(FEATURE_RX_PARALLEL_PWM)) {
if (isPWMDataBeingReceived()) { if (isPWMDataBeingReceived()) {
rxSignalReceivedNotDataDriven = true; rxSignalReceivedNotDataDriven = true;
rxIsInFailsafeModeNotDataDriven = false; rxIsInFailsafeModeNotDataDriven = false;
needRxSignalBefore = currentTime + needRxSignalMaxDelayUs; needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
} }
} else } else
#endif #endif
@ -340,10 +340,10 @@ bool rxUpdateCheck(uint32_t currentTime, uint32_t currentDeltaTime)
rxDataReceived = true; rxDataReceived = true;
rxIsInFailsafeMode = (frameStatus & RX_FRAME_FAILSAFE) != 0; rxIsInFailsafeMode = (frameStatus & RX_FRAME_FAILSAFE) != 0;
rxSignalReceived = !rxIsInFailsafeMode; rxSignalReceived = !rxIsInFailsafeMode;
needRxSignalBefore = currentTime + needRxSignalMaxDelayUs; needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
} }
} }
return rxDataReceived || (currentTime >= rxUpdateAt); // data driven or 50Hz return rxDataReceived || (currentTimeUs >= rxUpdateAt); // data driven or 50Hz
} }
static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample) static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
@ -448,11 +448,11 @@ static void readRxChannelsApplyRanges(void)
} }
} }
static void detectAndApplySignalLossBehaviour(uint32_t currentTime) static void detectAndApplySignalLossBehaviour(timeUs_t currentTimeUs)
{ {
bool useValueFromRx = true; bool useValueFromRx = true;
const bool rxIsDataDriven = isRxDataDriven(); const bool rxIsDataDriven = isRxDataDriven();
const uint32_t currentMilliTime = currentTime / 1000; const uint32_t currentMilliTime = currentTimeUs / 1000;
if (!rxIsDataDriven) { if (!rxIsDataDriven) {
rxSignalReceived = rxSignalReceivedNotDataDriven; rxSignalReceived = rxSignalReceivedNotDataDriven;
@ -513,20 +513,20 @@ static void detectAndApplySignalLossBehaviour(uint32_t currentTime)
#endif #endif
} }
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime) void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
{ {
rxUpdateAt = currentTime + DELAY_50_HZ; rxUpdateAt = currentTimeUs + DELAY_50_HZ;
// only proceed when no more samples to skip and suspend period is over // only proceed when no more samples to skip and suspend period is over
if (skipRxSamples) { if (skipRxSamples) {
if (currentTime > suspendRxSignalUntil) { if (currentTimeUs > suspendRxSignalUntil) {
skipRxSamples--; skipRxSamples--;
} }
return; return;
} }
readRxChannelsApplyRanges(); readRxChannelsApplyRanges();
detectAndApplySignalLossBehaviour(currentTime); detectAndApplySignalLossBehaviour(currentTimeUs);
rcSampleIndex++; rcSampleIndex++;
} }
@ -560,19 +560,19 @@ static void updateRSSIPWM(void)
#define RSSI_ADC_SAMPLE_COUNT 16 #define RSSI_ADC_SAMPLE_COUNT 16
//#define RSSI_SCALE (0xFFF / 100.0f) //#define RSSI_SCALE (0xFFF / 100.0f)
static void updateRSSIADC(uint32_t currentTime) static void updateRSSIADC(timeUs_t currentTimeUs)
{ {
#ifndef USE_ADC #ifndef USE_ADC
UNUSED(currentTime); UNUSED(currentTimeUs);
#else #else
static uint8_t adcRssiSamples[RSSI_ADC_SAMPLE_COUNT]; static uint8_t adcRssiSamples[RSSI_ADC_SAMPLE_COUNT];
static uint8_t adcRssiSampleIndex = 0; static uint8_t adcRssiSampleIndex = 0;
static uint32_t rssiUpdateAt = 0; static uint32_t rssiUpdateAt = 0;
if ((int32_t)(currentTime - rssiUpdateAt) < 0) { if ((int32_t)(currentTimeUs - rssiUpdateAt) < 0) {
return; return;
} }
rssiUpdateAt = currentTime + DELAY_50_HZ; rssiUpdateAt = currentTimeUs + DELAY_50_HZ;
int16_t adcRssiMean = 0; int16_t adcRssiMean = 0;
uint16_t adcRssiSample = adcGetChannel(ADC_RSSI); uint16_t adcRssiSample = adcGetChannel(ADC_RSSI);
@ -594,13 +594,13 @@ static void updateRSSIADC(uint32_t currentTime)
#endif #endif
} }
void updateRSSI(uint32_t currentTime) void updateRSSI(timeUs_t currentTimeUs)
{ {
if (rxConfig->rssi_channel > 0) { if (rxConfig->rssi_channel > 0) {
updateRSSIPWM(); updateRSSIPWM();
} else if (feature(FEATURE_RSSI_ADC)) { } else if (feature(FEATURE_RSSI_ADC)) {
updateRSSIADC(currentTime); updateRSSIADC(currentTimeUs);
} }
} }

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#include "common/time.h"
#define STICK_CHANNEL_COUNT 4 #define STICK_CHANNEL_COUNT 4
#define PWM_RANGE_ZERO 0 // FIXME should all usages of this be changed to use PWM_RANGE_MIN? #define PWM_RANGE_ZERO 0 // FIXME should all usages of this be changed to use PWM_RANGE_MIN?
@ -155,14 +157,14 @@ extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only need
struct modeActivationCondition_s; struct modeActivationCondition_s;
void rxInit(const rxConfig_t *rxConfig, const struct modeActivationCondition_s *modeActivationConditions); void rxInit(const rxConfig_t *rxConfig, const struct modeActivationCondition_s *modeActivationConditions);
void useRxConfig(const rxConfig_t *rxConfigToUse); void useRxConfig(const rxConfig_t *rxConfigToUse);
bool rxUpdateCheck(uint32_t currentTime, uint32_t currentDeltaTime); bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs);
bool rxIsReceivingSignal(void); bool rxIsReceivingSignal(void);
bool rxAreFlightChannelsValid(void); bool rxAreFlightChannelsValid(void);
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime); void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs);
void parseRcChannels(const char *input, rxConfig_t *rxConfig); void parseRcChannels(const char *input, rxConfig_t *rxConfig);
void updateRSSI(uint32_t currentTime); void updateRSSI(timeUs_t currentTimeUs);
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration); void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration);
void suspendRxSignal(void); void suspendRxSignal(void);

View file

@ -113,7 +113,7 @@ typedef struct {
/* Configuration */ /* Configuration */
const char * taskName; const char * taskName;
const char * subTaskName; const char * subTaskName;
bool (*checkFunc)(timeUs_t currentTimeUs, uint32_t currentDeltaTimeUs); bool (*checkFunc)(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs);
void (*taskFunc)(timeUs_t currentTimeUs); void (*taskFunc)(timeUs_t currentTimeUs);
uint32_t desiredPeriod; // target period of execution uint32_t desiredPeriod; // target period of execution
const uint8_t staticPriority; // dynamicPriority grows in steps of this size, shouldn't be zero const uint8_t staticPriority; // dynamicPriority grows in steps of this size, shouldn't be zero

View file

@ -88,9 +88,9 @@ static int32_t applySonarMedianFilter(int32_t newSonarReading)
return newSonarReading; return newSonarReading;
} }
void sonarUpdate(uint32_t currentTime) void sonarUpdate(timeUs_t currentTimeUs)
{ {
UNUSED(currentTime); UNUSED(currentTimeUs);
hcsr04_start_reading(); hcsr04_start_reading();
} }

View file

@ -17,9 +17,12 @@
#pragma once #pragma once
#include "sensors/battery.h" #include "common/time.h"
#include "drivers/sonar_hcsr04.h" #include "drivers/sonar_hcsr04.h"
#include "sensors/battery.h"
#define SONAR_OUT_OF_RANGE (-1) #define SONAR_OUT_OF_RANGE (-1)
extern int16_t sonarMaxRangeCm; extern int16_t sonarMaxRangeCm;
@ -27,7 +30,7 @@ extern int16_t sonarCfAltCm;
extern int16_t sonarMaxAltWithTiltCm; extern int16_t sonarMaxAltWithTiltCm;
void sonarInit(const sonarConfig_t *sonarConfig); void sonarInit(const sonarConfig_t *sonarConfig);
void sonarUpdate(uint32_t currentTime); void sonarUpdate(timeUs_t currentTimeUs);
int32_t sonarRead(void); int32_t sonarRead(void);
int32_t sonarCalculateAltitude(int32_t sonarDistance, float cosTiltAngle); int32_t sonarCalculateAltitude(int32_t sonarDistance, float cosTiltAngle);
int32_t sonarGetLatestAltitude(void); int32_t sonarGetLatestAltitude(void);

View file

@ -1482,10 +1482,10 @@ void bstProcessInCommand(void)
} }
} }
static void resetBstChecker(uint32_t currentTime) static void resetBstChecker(timeUs_t currentTimeUs)
{ {
if(needResetCheck) { if(needResetCheck) {
if(currentTime >= (resetBstTimer + BST_RESET_TIME)) if(currentTimeUs >= (resetBstTimer + BST_RESET_TIME))
{ {
bstTimeoutUserCallback(); bstTimeoutUserCallback();
needResetCheck = false; needResetCheck = false;
@ -1502,14 +1502,14 @@ static uint32_t next20hzUpdateAt_1 = 0;
static uint8_t sendCounter = 0; static uint8_t sendCounter = 0;
void taskBstMasterProcess(uint32_t currentTime) void taskBstMasterProcess(timeUs_t currentTimeUs)
{ {
if(coreProReady) { if(coreProReady) {
if(currentTime >= next02hzUpdateAt_1 && !bstWriteBusy()) { if(currentTimeUs >= next02hzUpdateAt_1 && !bstWriteBusy()) {
writeFCModeToBST(); writeFCModeToBST();
next02hzUpdateAt_1 = currentTime + UPDATE_AT_02HZ; next02hzUpdateAt_1 = currentTimeUs + UPDATE_AT_02HZ;
} }
if(currentTime >= next20hzUpdateAt_1 && !bstWriteBusy()) { if(currentTimeUs >= next20hzUpdateAt_1 && !bstWriteBusy()) {
if(sendCounter == 0) if(sendCounter == 0)
writeRCChannelToBST(); writeRCChannelToBST();
else if(sendCounter == 1) else if(sendCounter == 1)
@ -1517,7 +1517,7 @@ void taskBstMasterProcess(uint32_t currentTime)
sendCounter++; sendCounter++;
if(sendCounter > 1) if(sendCounter > 1)
sendCounter = 0; sendCounter = 0;
next20hzUpdateAt_1 = currentTime + UPDATE_AT_20HZ; next20hzUpdateAt_1 = currentTimeUs + UPDATE_AT_20HZ;
} }
if(sensors(SENSOR_GPS) && !bstWriteBusy()) if(sensors(SENSOR_GPS) && !bstWriteBusy())
@ -1529,7 +1529,7 @@ void taskBstMasterProcess(uint32_t currentTime)
stopMotors(); stopMotors();
systemReset(); systemReset();
} }
resetBstChecker(currentTime); resetBstChecker(currentTimeUs);
} }
/*************************************************************************************************/ /*************************************************************************************************/

View file

@ -19,7 +19,7 @@
void bstProcessInCommand(void); void bstProcessInCommand(void);
void bstSlaveProcessInCommand(void); void bstSlaveProcessInCommand(void);
void taskBstMasterProcess(uint32_t currentTime); void taskBstMasterProcess(timeUs_t currentTimeUs);
bool writeGpsPositionPrameToBST(void); bool writeGpsPositionPrameToBST(void);
bool writeRollPitchYawToBST(void); bool writeRollPitchYawToBST(void);

View file

@ -330,7 +330,7 @@ bool checkCrsfTelemetryState(void)
/* /*
* Called periodically by the scheduler * Called periodically by the scheduler
*/ */
void handleCrsfTelemetry(uint32_t currentTime) void handleCrsfTelemetry(timeUs_t currentTimeUs)
{ {
static uint32_t crsfLastCycleTime; static uint32_t crsfLastCycleTime;
@ -343,8 +343,8 @@ void handleCrsfTelemetry(uint32_t currentTime)
crsfRxSendTelemetryData(); crsfRxSendTelemetryData();
// Actual telemetry data only needs to be sent at a low frequency, ie 10Hz // Actual telemetry data only needs to be sent at a low frequency, ie 10Hz
if (currentTime >= crsfLastCycleTime + CRSF_CYCLETIME_US) { if (currentTimeUs >= crsfLastCycleTime + CRSF_CYCLETIME_US) {
crsfLastCycleTime = currentTime; crsfLastCycleTime = currentTimeUs;
processCrsf(); processCrsf();
} }
} }

View file

@ -19,6 +19,8 @@
#pragma once #pragma once
#include "common/time.h"
typedef enum { typedef enum {
CRSF_FRAME_START = 0, CRSF_FRAME_START = 0,
CRSF_FRAME_ATTITUDE = CRSF_FRAME_START, CRSF_FRAME_ATTITUDE = CRSF_FRAME_START,
@ -30,7 +32,7 @@ typedef enum {
void initCrsfTelemetry(void); void initCrsfTelemetry(void);
bool checkCrsfTelemetryState(void); bool checkCrsfTelemetryState(void);
void handleCrsfTelemetry(uint32_t currentTime); void handleCrsfTelemetry(timeUs_t currentTimeUs);
int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType); int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType);

View file

@ -200,9 +200,9 @@ uint8_t escTelemetryFrameStatus(void)
return frameStatus; return frameStatus;
} }
void escTelemetryProcess(uint32_t currentTime) void escTelemetryProcess(timeUs_t currentTimeUs)
{ {
uint32_t currentTimeMs = currentTime / 1000; const timeMs_t currentTimeMs = currentTimeUs / 1000;
if (!escTelemetryEnabled) { if (!escTelemetryEnabled) {
return; return;

View file

@ -1,5 +1,7 @@
#pragma once #pragma once
#include "common/time.h"
uint8_t escTelemetryFrameStatus(void); uint8_t escTelemetryFrameStatus(void);
bool escTelemetryInit(void); bool escTelemetryInit(void);
bool isEscTelemetryActive(void); bool isEscTelemetryActive(void);
@ -7,4 +9,4 @@ int16_t getEscTelemetryVbat(void);
int16_t getEscTelemetryCurrent(void); int16_t getEscTelemetryCurrent(void);
int16_t getEscTelemetryConsumption(void); int16_t getEscTelemetryConsumption(void);
void escTelemetryProcess(uint32_t currentTime); void escTelemetryProcess(timeUs_t currentTimeUs);

View file

@ -489,33 +489,33 @@ void checkHoTTTelemetryState(void)
freeHoTTTelemetryPort(); freeHoTTTelemetryPort();
} }
void handleHoTTTelemetry(uint32_t currentTime) void handleHoTTTelemetry(timeUs_t currentTimeUs)
{ {
static uint32_t serialTimer; static timeUs_t serialTimer;
if (!hottTelemetryEnabled) { if (!hottTelemetryEnabled) {
return; return;
} }
if (shouldPrepareHoTTMessages(currentTime)) { if (shouldPrepareHoTTMessages(currentTimeUs)) {
hottPrepareMessages(); hottPrepareMessages();
lastMessagesPreparedAt = currentTime; lastMessagesPreparedAt = currentTimeUs;
} }
if (shouldCheckForHoTTRequest()) { if (shouldCheckForHoTTRequest()) {
hottCheckSerialData(currentTime); hottCheckSerialData(currentTimeUs);
} }
if (!hottMsg) if (!hottMsg)
return; return;
if (hottIsSending) { if (hottIsSending) {
if(currentTime - serialTimer < HOTT_TX_DELAY_US) { if(currentTimeUs - serialTimer < HOTT_TX_DELAY_US) {
return; return;
} }
} }
hottSendTelemetryData(); hottSendTelemetryData();
serialTimer = currentTime; serialTimer = currentTimeUs;
} }
#endif #endif

View file

@ -25,6 +25,8 @@
#pragma once #pragma once
#include "common/time.h"
#define HOTTV4_RXTX 4 #define HOTTV4_RXTX 4
#define HOTTV4_TEXT_MODE_REQUEST_ID 0x7f #define HOTTV4_TEXT_MODE_REQUEST_ID 0x7f
@ -485,7 +487,7 @@ typedef struct HOTT_AIRESC_MSG_s {
uint8_t stop_byte; //#44 constant value 0x7d uint8_t stop_byte; //#44 constant value 0x7d
} HOTT_AIRESC_MSG_t; } HOTT_AIRESC_MSG_t;
void handleHoTTTelemetry(uint32_t currentTime); void handleHoTTTelemetry(timeUs_t currentTimeUs);
void checkHoTTTelemetryState(void); void checkHoTTTelemetryState(void);
void initHoTTTelemetry(telemetryConfig_t *telemetryConfig); void initHoTTTelemetry(telemetryConfig_t *telemetryConfig);