mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
currentTime passed in scheduler task call
This commit is contained in:
parent
7122689038
commit
2f9ca4355c
21 changed files with 134 additions and 125 deletions
|
@ -323,9 +323,6 @@ typedef struct blackboxSlowState_s {
|
||||||
//From mixer.c:
|
//From mixer.c:
|
||||||
extern uint8_t motorCount;
|
extern uint8_t motorCount;
|
||||||
|
|
||||||
//From mw.c:
|
|
||||||
extern uint32_t currentTime;
|
|
||||||
|
|
||||||
//From rx.c:
|
//From rx.c:
|
||||||
extern uint16_t rssi;
|
extern uint16_t rssi;
|
||||||
|
|
||||||
|
@ -965,7 +962,7 @@ static void writeGPSHomeFrame()
|
||||||
gpsHistory.GPS_home[1] = GPS_home[1];
|
gpsHistory.GPS_home[1] = GPS_home[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
static void writeGPSFrame()
|
static void writeGPSFrame(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
blackboxWrite('G');
|
blackboxWrite('G');
|
||||||
|
|
||||||
|
@ -996,7 +993,7 @@ static void writeGPSFrame()
|
||||||
/**
|
/**
|
||||||
* 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(void)
|
static void loadMainState(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
|
blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
|
||||||
int i;
|
int i;
|
||||||
|
@ -1428,7 +1425,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()
|
static void blackboxLogIteration(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
// 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()) {
|
||||||
|
@ -1438,7 +1435,7 @@ static void blackboxLogIteration()
|
||||||
*/
|
*/
|
||||||
writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
|
writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
|
||||||
|
|
||||||
loadMainState();
|
loadMainState(currentTime);
|
||||||
writeIntraframe();
|
writeIntraframe();
|
||||||
} else {
|
} else {
|
||||||
blackboxCheckAndLogArmingBeep();
|
blackboxCheckAndLogArmingBeep();
|
||||||
|
@ -1451,7 +1448,7 @@ static void blackboxLogIteration()
|
||||||
*/
|
*/
|
||||||
writeSlowFrameIfNeeded(true);
|
writeSlowFrameIfNeeded(true);
|
||||||
|
|
||||||
loadMainState();
|
loadMainState(currentTime);
|
||||||
writeInterframe();
|
writeInterframe();
|
||||||
}
|
}
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
@ -1467,11 +1464,11 @@ static void blackboxLogIteration()
|
||||||
|| (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
|
|| (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
|
||||||
|
|
||||||
writeGPSHomeFrame();
|
writeGPSHomeFrame();
|
||||||
writeGPSFrame();
|
writeGPSFrame(currentTime);
|
||||||
} 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();
|
writeGPSFrame(currentTime);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -1484,7 +1481,7 @@ static void blackboxLogIteration()
|
||||||
/**
|
/**
|
||||||
* Call each flight loop iteration to perform blackbox logging.
|
* Call each flight loop iteration to perform blackbox logging.
|
||||||
*/
|
*/
|
||||||
void handleBlackbox(void)
|
void handleBlackbox(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
int i;
|
int i;
|
||||||
|
|
||||||
|
@ -1581,7 +1578,7 @@ void handleBlackbox(void)
|
||||||
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();
|
blackboxLogIteration(currentTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Keep the logging timers ticking so our log iteration continues to advance
|
// Keep the logging timers ticking so our log iteration continues to advance
|
||||||
|
@ -1593,7 +1590,7 @@ void handleBlackbox(void)
|
||||||
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();
|
blackboxLogIteration(currentTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
blackboxAdvanceIterationTimers();
|
blackboxAdvanceIterationTimers();
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
|
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
|
||||||
|
|
||||||
void initBlackbox(void);
|
void initBlackbox(void);
|
||||||
void handleBlackbox(void);
|
void handleBlackbox(uint32_t currentTime);
|
||||||
void startBlackbox(void);
|
void startBlackbox(void);
|
||||||
void finishBlackbox(void);
|
void finishBlackbox(void);
|
||||||
|
|
||||||
|
|
|
@ -119,7 +119,6 @@ uint8_t motorControlEnable = false;
|
||||||
int16_t telemTemperature1; // gyro sensor temperature
|
int16_t telemTemperature1; // gyro sensor temperature
|
||||||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||||
|
|
||||||
extern uint32_t currentTime;
|
|
||||||
extern uint8_t PIDweight[3];
|
extern uint8_t PIDweight[3];
|
||||||
|
|
||||||
uint16_t filteredCycleTime;
|
uint16_t filteredCycleTime;
|
||||||
|
@ -537,7 +536,7 @@ void updateMagHold(void)
|
||||||
magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
|
magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
|
||||||
}
|
}
|
||||||
|
|
||||||
void processRx(void)
|
void processRx(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
static bool armedBeeperOn = false;
|
static bool armedBeeperOn = false;
|
||||||
static bool airmodeIsActivated;
|
static bool airmodeIsActivated;
|
||||||
|
@ -741,7 +740,8 @@ void subTaskPidController(void)
|
||||||
if (debugMode == DEBUG_PIDLOOP) {debug[2] = micros() - startTime;}
|
if (debugMode == DEBUG_PIDLOOP) {debug[2] = micros() - startTime;}
|
||||||
}
|
}
|
||||||
|
|
||||||
void subTaskMainSubprocesses(void) {
|
void subTaskMainSubprocesses(void)
|
||||||
|
{
|
||||||
|
|
||||||
const uint32_t startTime = micros();
|
const uint32_t startTime = micros();
|
||||||
|
|
||||||
|
@ -807,12 +807,12 @@ void subTaskMainSubprocesses(void) {
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef BLACKBOX
|
||||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||||
handleBlackbox();
|
handleBlackbox(startTime);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
updateTransponder();
|
updateTransponder(startTime);
|
||||||
#endif
|
#endif
|
||||||
if (debugMode == DEBUG_PIDLOOP) {debug[1] = micros() - startTime;}
|
if (debugMode == DEBUG_PIDLOOP) {debug[1] = micros() - startTime;}
|
||||||
}
|
}
|
||||||
|
@ -841,7 +841,8 @@ void subTaskMotorUpdate(void)
|
||||||
if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;}
|
if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t setPidUpdateCountDown(void) {
|
uint8_t setPidUpdateCountDown(void)
|
||||||
|
{
|
||||||
if (masterConfig.gyro_soft_lpf_hz) {
|
if (masterConfig.gyro_soft_lpf_hz) {
|
||||||
return masterConfig.pid_process_denom - 1;
|
return masterConfig.pid_process_denom - 1;
|
||||||
} else {
|
} else {
|
||||||
|
@ -850,8 +851,11 @@ uint8_t setPidUpdateCountDown(void) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Function for loop trigger
|
// Function for loop trigger
|
||||||
void taskMainPidLoopCheck(void)
|
void taskMainPidLoopCheck(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
|
static uint32_t previousTime;
|
||||||
static bool runTaskMainSubprocesses;
|
static bool runTaskMainSubprocesses;
|
||||||
static uint8_t pidUpdateCountdown;
|
static uint8_t pidUpdateCountdown;
|
||||||
|
|
||||||
|
@ -879,26 +883,33 @@ void taskMainPidLoopCheck(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateAccelerometer(void)
|
void taskUpdateAccelerometer(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
imuUpdateAccelerometer(&masterConfig.accelerometerTrims);
|
imuUpdateAccelerometer(&masterConfig.accelerometerTrims);
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateAttitude(void) {
|
void taskUpdateAttitude(uint32_t currentTime)
|
||||||
imuUpdateAttitude();
|
{
|
||||||
|
imuUpdateAttitude(currentTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskHandleSerial(void)
|
void taskHandleSerial(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
handleSerial();
|
handleSerial();
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateBeeper(void)
|
void taskUpdateBeeper(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
beeperUpdate(); //call periodic beeper handler
|
beeperUpdate(); //call periodic beeper handler
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateBattery(void)
|
void taskUpdateBattery(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
#ifdef USE_ADC
|
#ifdef USE_ADC
|
||||||
static uint32_t vbatLastServiced = 0;
|
static uint32_t vbatLastServiced = 0;
|
||||||
|
@ -912,7 +923,7 @@ void taskUpdateBattery(void)
|
||||||
|
|
||||||
static uint32_t ibatLastServiced = 0;
|
static uint32_t ibatLastServiced = 0;
|
||||||
if (feature(FEATURE_CURRENT_METER)) {
|
if (feature(FEATURE_CURRENT_METER)) {
|
||||||
int32_t ibatTimeSinceLastServiced = cmp32(currentTime, ibatLastServiced);
|
const int32_t ibatTimeSinceLastServiced = cmp32(currentTime, ibatLastServiced);
|
||||||
|
|
||||||
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
||||||
ibatLastServiced = currentTime;
|
ibatLastServiced = currentTime;
|
||||||
|
@ -921,16 +932,17 @@ void taskUpdateBattery(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool taskUpdateRxCheck(uint32_t currentDeltaTime)
|
bool taskUpdateRxCheck(uint32_t currentTime, uint32_t currentDeltaTime)
|
||||||
{
|
{
|
||||||
UNUSED(currentDeltaTime);
|
UNUSED(currentDeltaTime);
|
||||||
updateRx(currentTime);
|
|
||||||
|
updateRx(currentTime);
|
||||||
return shouldProcessRx(currentTime);
|
return shouldProcessRx(currentTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateRxMain(void)
|
void taskUpdateRxMain(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
processRx();
|
processRx(currentTime);
|
||||||
isRXDataNew = true;
|
isRXDataNew = true;
|
||||||
|
|
||||||
#if !defined(BARO) && !defined(SONAR)
|
#if !defined(BARO) && !defined(SONAR)
|
||||||
|
@ -953,8 +965,10 @@ void taskUpdateRxMain(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
void taskProcessGPS(void)
|
void taskProcessGPS(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
|
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
|
||||||
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
|
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
|
||||||
// change this based on available hardware
|
// change this based on available hardware
|
||||||
|
@ -969,17 +983,19 @@ void taskProcessGPS(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
void taskUpdateCompass(void)
|
void taskUpdateCompass(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
updateCompass(&masterConfig.magZero);
|
updateCompass(currentTime, &masterConfig.magZero);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
void taskUpdateBaro(void)
|
void taskUpdateBaro(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
uint32_t newDeadline = baroUpdate();
|
uint32_t newDeadline = baroUpdate();
|
||||||
rescheduleTask(TASK_SELF, newDeadline);
|
rescheduleTask(TASK_SELF, newDeadline);
|
||||||
|
@ -988,8 +1004,10 @@ void taskUpdateBaro(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef SONAR
|
||||||
void taskUpdateSonar(void)
|
void taskUpdateSonar(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
if (sensors(SENSOR_SONAR)) {
|
if (sensors(SENSOR_SONAR)) {
|
||||||
sonarUpdate();
|
sonarUpdate();
|
||||||
}
|
}
|
||||||
|
@ -997,7 +1015,7 @@ void taskUpdateSonar(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(BARO) || defined(SONAR)
|
||||||
void taskCalculateAltitude(void)
|
void taskCalculateAltitude(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (false
|
if (false
|
||||||
#if defined(BARO)
|
#if defined(BARO)
|
||||||
|
@ -1012,17 +1030,19 @@ void taskCalculateAltitude(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DISPLAY
|
#ifdef DISPLAY
|
||||||
void taskUpdateDisplay(void)
|
void taskUpdateDisplay(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (feature(FEATURE_DISPLAY)) {
|
if (feature(FEATURE_DISPLAY)) {
|
||||||
updateDisplay();
|
updateDisplay(currentTime);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
void taskTelemetry(void)
|
void taskTelemetry(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
|
UNUSED(currentTime);
|
||||||
|
|
||||||
telemetryCheckState();
|
telemetryCheckState();
|
||||||
|
|
||||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||||
|
@ -1032,28 +1052,28 @@ void taskTelemetry(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
void taskLedStrip(void)
|
void taskLedStrip(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (feature(FEATURE_LED_STRIP)) {
|
if (feature(FEATURE_LED_STRIP)) {
|
||||||
updateLedStrip();
|
updateLedStrip(currentTime);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
void taskTransponder(void)
|
void taskTransponder(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (feature(FEATURE_TRANSPONDER)) {
|
if (feature(FEATURE_TRANSPONDER)) {
|
||||||
updateTransponder();
|
updateTransponder(currentTime);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef OSD
|
||||||
void taskUpdateOsd(void)
|
void taskUpdateOsd(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (feature(FEATURE_OSD)) {
|
if (feature(FEATURE_OSD)) {
|
||||||
updateOsd();
|
updateOsd(currentTime);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -374,7 +374,7 @@ static bool isMagnetometerHealthy(void)
|
||||||
return (magADC[X] != 0) && (magADC[Y] != 0) && (magADC[Z] != 0);
|
return (magADC[X] != 0) && (magADC[Y] != 0) && (magADC[Z] != 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void imuCalculateEstimatedAttitude(void)
|
static void imuCalculateEstimatedAttitude(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
static uint32_t previousIMUUpdateTime;
|
static uint32_t previousIMUUpdateTime;
|
||||||
float rawYawError = 0;
|
float rawYawError = 0;
|
||||||
|
@ -382,7 +382,6 @@ static void imuCalculateEstimatedAttitude(void)
|
||||||
bool useMag = false;
|
bool useMag = false;
|
||||||
bool useYaw = false;
|
bool useYaw = false;
|
||||||
|
|
||||||
uint32_t currentTime = micros();
|
|
||||||
uint32_t deltaT = currentTime - previousIMUUpdateTime;
|
uint32_t deltaT = currentTime - previousIMUUpdateTime;
|
||||||
previousIMUUpdateTime = currentTime;
|
previousIMUUpdateTime = currentTime;
|
||||||
|
|
||||||
|
@ -420,10 +419,10 @@ void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void imuUpdateAttitude(void)
|
void imuUpdateAttitude(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) {
|
if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) {
|
||||||
imuCalculateEstimatedAttitude();
|
imuCalculateEstimatedAttitude(currentTime);
|
||||||
} else {
|
} else {
|
||||||
accSmooth[X] = 0;
|
accSmooth[X] = 0;
|
||||||
accSmooth[Y] = 0;
|
accSmooth[Y] = 0;
|
||||||
|
|
|
@ -80,7 +80,7 @@ void imuConfigure(
|
||||||
float getCosTiltAngle(void);
|
float getCosTiltAngle(void);
|
||||||
void calculateEstimatedAltitude(uint32_t currentTime);
|
void calculateEstimatedAltitude(uint32_t currentTime);
|
||||||
void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims);
|
void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims);
|
||||||
void imuUpdateAttitude(void);
|
void imuUpdateAttitude(uint32_t currentTime);
|
||||||
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);
|
||||||
|
|
|
@ -582,17 +582,16 @@ void showDebugPage(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void updateDisplay(void)
|
void updateDisplay(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
uint32_t now = micros();
|
|
||||||
static uint8_t previousArmedState = 0;
|
static uint8_t previousArmedState = 0;
|
||||||
|
|
||||||
bool updateNow = (int32_t)(now - nextDisplayUpdateAt) >= 0L;
|
const bool updateNow = (int32_t)(currentTime - nextDisplayUpdateAt) >= 0L;
|
||||||
if (!updateNow) {
|
if (!updateNow) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
nextDisplayUpdateAt = now + DISPLAY_UPDATE_FREQUENCY;
|
nextDisplayUpdateAt = currentTime + 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;
|
||||||
|
@ -612,7 +611,7 @@ void updateDisplay(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) ||
|
pageState.pageChanging = (pageState.pageFlags & PAGE_STATE_FLAG_FORCE_PAGE_CHANGE) ||
|
||||||
(((int32_t)(now - pageState.nextPageAt) >= 0L && (pageState.pageFlags & PAGE_STATE_FLAG_CYCLE_ENABLED)));
|
(((int32_t)(currentTime - 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;
|
||||||
|
@ -622,7 +621,7 @@ void updateDisplay(void)
|
||||||
|
|
||||||
if (pageState.pageChanging) {
|
if (pageState.pageChanging) {
|
||||||
pageState.pageFlags &= ~PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
|
pageState.pageFlags &= ~PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
|
||||||
pageState.nextPageAt = now + PAGE_CYCLE_FREQUENCY;
|
pageState.nextPageAt = currentTime + 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
|
||||||
|
@ -703,7 +702,7 @@ void displayInit(rxConfig_t *rxConfigToUse)
|
||||||
memset(&pageState, 0, sizeof(pageState));
|
memset(&pageState, 0, sizeof(pageState));
|
||||||
displaySetPage(PAGE_WELCOME);
|
displaySetPage(PAGE_WELCOME);
|
||||||
|
|
||||||
updateDisplay();
|
updateDisplay(micros());
|
||||||
|
|
||||||
displaySetNextPageChangeAt(micros() + (1000 * 1000 * 5));
|
displaySetNextPageChangeAt(micros() + (1000 * 1000 * 5));
|
||||||
}
|
}
|
||||||
|
|
|
@ -37,7 +37,7 @@ typedef enum {
|
||||||
|
|
||||||
struct rxConfig_s;
|
struct rxConfig_s;
|
||||||
void displayInit(struct rxConfig_s *intialRxConfig);
|
void displayInit(struct rxConfig_s *intialRxConfig);
|
||||||
void updateDisplay(void);
|
void updateDisplay(uint32_t currentTime);
|
||||||
|
|
||||||
void displayShowFixedPage(pageId_e pageId);
|
void displayShowFixedPage(pageId_e pageId);
|
||||||
|
|
||||||
|
|
|
@ -1065,7 +1065,7 @@ static void gpsHandlePassthrough(uint8_t data)
|
||||||
gpsNewData(data);
|
gpsNewData(data);
|
||||||
#ifdef DISPLAY
|
#ifdef DISPLAY
|
||||||
if (feature(FEATURE_DISPLAY)) {
|
if (feature(FEATURE_DISPLAY)) {
|
||||||
updateDisplay();
|
updateDisplay(micros());
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -925,7 +925,7 @@ static applyLayerFn_timed* layerTable[] = {
|
||||||
[timRing] = &applyLedThrustRingLayer
|
[timRing] = &applyLedThrustRingLayer
|
||||||
};
|
};
|
||||||
|
|
||||||
void updateLedStrip(void)
|
void updateLedStrip(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if (!(ledStripInitialised && isWS2811LedStripReady())) {
|
if (!(ledStripInitialised && isWS2811LedStripReady())) {
|
||||||
return;
|
return;
|
||||||
|
@ -940,7 +940,7 @@ void updateLedStrip(void)
|
||||||
}
|
}
|
||||||
ledStripEnabled = true;
|
ledStripEnabled = true;
|
||||||
|
|
||||||
uint32_t now = micros();
|
const uint32_t now = currentTime;
|
||||||
|
|
||||||
// test all led timers, setting corresponding bits
|
// test all led timers, setting corresponding bits
|
||||||
uint32_t timActive = 0;
|
uint32_t timActive = 0;
|
||||||
|
|
|
@ -165,7 +165,7 @@ void reevaluateLedConfig(void);
|
||||||
|
|
||||||
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, modeColorIndexes_t *modeColorsToUse, specialColorIndexes_t *specialColorsToUse);
|
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, modeColorIndexes_t *modeColorsToUse, specialColorIndexes_t *specialColorsToUse);
|
||||||
void ledStripEnable(void);
|
void ledStripEnable(void);
|
||||||
void updateLedStrip(void);
|
void updateLedStrip(uint32_t currentTime);
|
||||||
|
|
||||||
bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex);
|
bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex);
|
||||||
|
|
||||||
|
|
|
@ -701,32 +701,31 @@ void osdDrawArtificialHorizon(int rollAngle, int pitchAngle, uint8_t show_sideba
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateOsd(void)
|
void updateOsd(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
static uint8_t blink = 0;
|
static uint8_t blink = 0;
|
||||||
static uint8_t arming = 0;
|
static uint8_t arming = 0;
|
||||||
uint32_t seconds;
|
uint32_t seconds;
|
||||||
char line[30];
|
char line[30];
|
||||||
uint32_t now = micros();
|
|
||||||
|
|
||||||
bool updateNow = (int32_t)(now - next_osd_update_at) >= 0L;
|
const bool updateNow = (int32_t)(currentTime - next_osd_update_at) >= 0L;
|
||||||
if (!updateNow) {
|
if (!updateNow) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
next_osd_update_at = now + OSD_UPDATE_FREQUENCY;
|
next_osd_update_at = currentTime + OSD_UPDATE_FREQUENCY;
|
||||||
blink++;
|
blink++;
|
||||||
|
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
if (!armed) {
|
if (!armed) {
|
||||||
armed = true;
|
armed = true;
|
||||||
armed_at = now;
|
armed_at = currentTime;
|
||||||
in_menu = false;
|
in_menu = false;
|
||||||
arming = 5;
|
arming = 5;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (armed) {
|
if (armed) {
|
||||||
armed = false;
|
armed = false;
|
||||||
armed_seconds += ((now - armed_at) / 1000000);
|
armed_seconds += ((currentTime - armed_at) / 1000000);
|
||||||
}
|
}
|
||||||
for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) {
|
for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) {
|
||||||
sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
|
sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
|
||||||
|
@ -792,12 +791,12 @@ void updateOsd(void)
|
||||||
}
|
}
|
||||||
if (masterConfig.osdProfile.item_pos[OSD_TIMER] != -1) {
|
if (masterConfig.osdProfile.item_pos[OSD_TIMER] != -1) {
|
||||||
if (armed) {
|
if (armed) {
|
||||||
seconds = armed_seconds + ((now-armed_at) / 1000000);
|
seconds = armed_seconds + ((currentTime - armed_at) / 1000000);
|
||||||
line[0] = SYM_FLY_M;
|
line[0] = SYM_FLY_M;
|
||||||
sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60);
|
sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60);
|
||||||
} else {
|
} else {
|
||||||
line[0] = SYM_ON_M;
|
line[0] = SYM_ON_M;
|
||||||
seconds = now / 1000000;
|
seconds = currentTime / 1000000;
|
||||||
sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60);
|
sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60);
|
||||||
}
|
}
|
||||||
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_TIMER]);
|
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_TIMER]);
|
||||||
|
|
|
@ -63,6 +63,6 @@ typedef struct {
|
||||||
int16_t item_pos[OSD_MAX_ITEMS];
|
int16_t item_pos[OSD_MAX_ITEMS];
|
||||||
} osd_profile;
|
} osd_profile;
|
||||||
|
|
||||||
void updateOsd(void);
|
void updateOsd(uint32_t currentTime);
|
||||||
void osdInit(void);
|
void osdInit(void);
|
||||||
void resetOsdConfig(osd_profile *osdProfile);
|
void resetOsdConfig(osd_profile *osdProfile);
|
||||||
|
|
|
@ -42,7 +42,7 @@ static uint32_t nextUpdateAt = 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 updateTransponder(void)
|
void updateTransponder(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
static uint32_t jitterIndex = 0;
|
static uint32_t jitterIndex = 0;
|
||||||
|
|
||||||
|
@ -50,9 +50,7 @@ void updateTransponder(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t now = micros();
|
const bool updateNow = (int32_t)(currentTime - nextUpdateAt) >= 0L;
|
||||||
|
|
||||||
bool updateNow = (int32_t)(now - nextUpdateAt) >= 0L;
|
|
||||||
if (!updateNow) {
|
if (!updateNow) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -63,12 +61,12 @@ void updateTransponder(void)
|
||||||
jitterIndex = 0;
|
jitterIndex = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
nextUpdateAt = now + 4500 + jitter;
|
nextUpdateAt = currentTime + 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 = now + (1000 * 1000) / 10; // 10 hz.
|
nextUpdateAt = currentTime + (1000 * 1000) / 10; // 10 hz.
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,7 @@ void transponderInit(uint8_t* transponderCode);
|
||||||
|
|
||||||
void transponderEnable(void);
|
void transponderEnable(void);
|
||||||
void transponderDisable(void);
|
void transponderDisable(void);
|
||||||
void updateTransponder(void);
|
void updateTransponder(uint32_t currentTime);
|
||||||
void transponderUpdateData(uint8_t* transponderData);
|
void transponderUpdateData(uint8_t* transponderData);
|
||||||
void transponderTransmitOnce(void);
|
void transponderTransmitOnce(void);
|
||||||
void transponderStartRepeating(void);
|
void transponderStartRepeating(void);
|
||||||
|
|
|
@ -38,7 +38,6 @@ static cfTask_t *currentTask = NULL;
|
||||||
static uint32_t totalWaitingTasks;
|
static uint32_t totalWaitingTasks;
|
||||||
static uint32_t totalWaitingTasksSamples;
|
static uint32_t totalWaitingTasksSamples;
|
||||||
|
|
||||||
uint32_t currentTime = 0;
|
|
||||||
uint16_t averageSystemLoadPercent = 0;
|
uint16_t averageSystemLoadPercent = 0;
|
||||||
|
|
||||||
|
|
||||||
|
@ -110,9 +109,11 @@ cfTask_t *queueNext(void)
|
||||||
return taskQueueArray[++taskQueuePos]; // guaranteed to be NULL at end of queue
|
return taskQueueArray[++taskQueuePos]; // guaranteed to be NULL at end of queue
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskSystem(void)
|
void taskSystem(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
/* Calculate system load */
|
UNUSED(currentTime);
|
||||||
|
|
||||||
|
// Calculate system load
|
||||||
if (totalWaitingTasksSamples > 0) {
|
if (totalWaitingTasksSamples > 0) {
|
||||||
averageSystemLoadPercent = 100 * totalWaitingTasks / totalWaitingTasksSamples;
|
averageSystemLoadPercent = 100 * totalWaitingTasks / totalWaitingTasksSamples;
|
||||||
totalWaitingTasksSamples = 0;
|
totalWaitingTasksSamples = 0;
|
||||||
|
@ -174,7 +175,7 @@ void schedulerInit(void)
|
||||||
void scheduler(void)
|
void scheduler(void)
|
||||||
{
|
{
|
||||||
// Cache currentTime
|
// Cache currentTime
|
||||||
currentTime = micros();
|
const uint32_t currentTime = micros();
|
||||||
|
|
||||||
// Check for realtime tasks
|
// Check for realtime tasks
|
||||||
uint32_t timeToNextRealtimeTask = UINT32_MAX;
|
uint32_t timeToNextRealtimeTask = UINT32_MAX;
|
||||||
|
@ -203,7 +204,7 @@ void scheduler(void)
|
||||||
task->taskAgeCycles = 1 + ((currentTime - task->lastSignaledAt) / task->desiredPeriod);
|
task->taskAgeCycles = 1 + ((currentTime - task->lastSignaledAt) / task->desiredPeriod);
|
||||||
task->dynamicPriority = 1 + task->staticPriority * task->taskAgeCycles;
|
task->dynamicPriority = 1 + task->staticPriority * task->taskAgeCycles;
|
||||||
waitingTasks++;
|
waitingTasks++;
|
||||||
} else if (task->checkFunc(currentTime - task->lastExecutedAt)) {
|
} else if (task->checkFunc(currentTime, currentTime - task->lastExecutedAt)) {
|
||||||
task->lastSignaledAt = currentTime;
|
task->lastSignaledAt = currentTime;
|
||||||
task->taskAgeCycles = 1;
|
task->taskAgeCycles = 1;
|
||||||
task->dynamicPriority = 1 + task->staticPriority;
|
task->dynamicPriority = 1 + task->staticPriority;
|
||||||
|
@ -246,7 +247,7 @@ void scheduler(void)
|
||||||
|
|
||||||
// Execute task
|
// Execute task
|
||||||
const uint32_t currentTimeBeforeTaskCall = micros();
|
const uint32_t currentTimeBeforeTaskCall = micros();
|
||||||
selectedTask->taskFunc();
|
selectedTask->taskFunc(currentTimeBeforeTaskCall);
|
||||||
const uint32_t taskExecutionTime = micros() - currentTimeBeforeTaskCall;
|
const uint32_t taskExecutionTime = micros() - currentTimeBeforeTaskCall;
|
||||||
|
|
||||||
selectedTask->averageExecutionTime = ((uint32_t)selectedTask->averageExecutionTime * 31 + taskExecutionTime) / 32;
|
selectedTask->averageExecutionTime = ((uint32_t)selectedTask->averageExecutionTime * 31 + taskExecutionTime) / 32;
|
||||||
|
|
|
@ -98,8 +98,8 @@ typedef struct {
|
||||||
/* Configuration */
|
/* Configuration */
|
||||||
const char * taskName;
|
const char * taskName;
|
||||||
const char * subTaskName;
|
const char * subTaskName;
|
||||||
bool (*checkFunc)(uint32_t currentDeltaTime);
|
bool (*checkFunc)(uint32_t currentTime, uint32_t currentDeltaTime);
|
||||||
void (*taskFunc)(void);
|
void (*taskFunc)(uint32_t currentTime);
|
||||||
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
|
||||||
|
|
||||||
|
|
|
@ -17,29 +17,29 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
void taskSystem(void);
|
void taskSystem(uint32_t currentTime);
|
||||||
void taskMainPidLoopCheck(void);
|
void taskMainPidLoopCheck(uint32_t currentTime);
|
||||||
void taskUpdateAccelerometer(void);
|
void taskUpdateAccelerometer(uint32_t currentTime);
|
||||||
void taskUpdateAttitude(void);
|
void taskUpdateAttitude(uint32_t currentTime);
|
||||||
bool taskUpdateRxCheck(uint32_t currentDeltaTime);
|
bool taskUpdateRxCheck(uint32_t currentTime, uint32_t currentDeltaTime);
|
||||||
void taskUpdateRxMain(void);
|
void taskUpdateRxMain(uint32_t currentTime);
|
||||||
void taskHandleSerial(void);
|
void taskHandleSerial(uint32_t currentTime);
|
||||||
void taskUpdateBattery(void);
|
void taskUpdateBattery(uint32_t currentTime);
|
||||||
void taskUpdateBeeper(void);
|
void taskUpdateBeeper(uint32_t currentTime);
|
||||||
void taskProcessGPS(void);
|
void taskProcessGPS(uint32_t currentTime);
|
||||||
void taskUpdateCompass(void);
|
void taskUpdateCompass(uint32_t currentTime);
|
||||||
void taskUpdateBaro(void);
|
void taskUpdateBaro(uint32_t currentTime);
|
||||||
void taskUpdateSonar(void);
|
void taskUpdateSonar(uint32_t currentTime);
|
||||||
void taskCalculateAltitude(void);
|
void taskCalculateAltitude(uint32_t currentTime);
|
||||||
void taskUpdateDisplay(void);
|
void taskUpdateDisplay(uint32_t currentTime);
|
||||||
void taskTelemetry(void);
|
void taskTelemetry(uint32_t currentTime);
|
||||||
void taskLedStrip(void);
|
void taskLedStrip(uint32_t currentTime);
|
||||||
void taskTransponder(void);
|
void taskTransponder(uint32_t currentTime);
|
||||||
#ifdef OSD
|
#ifdef OSD
|
||||||
void taskUpdateOsd(void);
|
void taskUpdateOsd(uint32_t currentTime);
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
void taskBstReadWrite(void);
|
void taskBstReadWrite(uint32_t currentTime);
|
||||||
void taskBstMasterProcess(void);
|
void taskBstMasterProcess(uint32_t currentTime);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -45,8 +45,6 @@ sensor_align_e magAlign = 0;
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
|
|
||||||
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
|
|
||||||
|
|
||||||
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
||||||
static uint8_t magInit = 0;
|
static uint8_t magInit = 0;
|
||||||
|
|
||||||
|
@ -59,7 +57,7 @@ void compassInit(void)
|
||||||
magInit = 1;
|
magInit = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateCompass(flightDynamicsTrims_t *magZero)
|
void updateCompass(uint32_t currentTime, flightDynamicsTrims_t *magZero)
|
||||||
{
|
{
|
||||||
static uint32_t tCal = 0;
|
static uint32_t tCal = 0;
|
||||||
static flightDynamicsTrims_t magZeroTempMin;
|
static flightDynamicsTrims_t magZeroTempMin;
|
||||||
|
|
|
@ -29,7 +29,7 @@ typedef enum {
|
||||||
|
|
||||||
void compassInit(void);
|
void compassInit(void);
|
||||||
union flightDynamicsTrims_u;
|
union flightDynamicsTrims_u;
|
||||||
void updateCompass(union flightDynamicsTrims_u *magZero);
|
void updateCompass(uint32_t currentTime, union flightDynamicsTrims_u *magZero);
|
||||||
|
|
||||||
extern int32_t magADC[XYZ_AXIS_COUNT];
|
extern int32_t magADC[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
|
|
@ -1479,11 +1479,10 @@ void bstProcessInCommand(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void resetBstChecker(void)
|
static void resetBstChecker(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if(needResetCheck) {
|
if(needResetCheck) {
|
||||||
uint32_t currentTimer = micros();
|
if(currentTime >= (resetBstTimer + BST_RESET_TIME))
|
||||||
if(currentTimer >= (resetBstTimer + BST_RESET_TIME))
|
|
||||||
{
|
{
|
||||||
bstTimeoutUserCallback();
|
bstTimeoutUserCallback();
|
||||||
needResetCheck = false;
|
needResetCheck = false;
|
||||||
|
@ -1500,15 +1499,14 @@ static uint32_t next20hzUpdateAt_1 = 0;
|
||||||
|
|
||||||
static uint8_t sendCounter = 0;
|
static uint8_t sendCounter = 0;
|
||||||
|
|
||||||
void taskBstMasterProcess(void)
|
void taskBstMasterProcess(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
if(coreProReady) {
|
if(coreProReady) {
|
||||||
uint32_t now = micros();
|
if(currentTime >= next02hzUpdateAt_1 && !bstWriteBusy()) {
|
||||||
if(now >= next02hzUpdateAt_1 && !bstWriteBusy()) {
|
|
||||||
writeFCModeToBST();
|
writeFCModeToBST();
|
||||||
next02hzUpdateAt_1 = now + UPDATE_AT_02HZ;
|
next02hzUpdateAt_1 = currentTime + UPDATE_AT_02HZ;
|
||||||
}
|
}
|
||||||
if(now >= next20hzUpdateAt_1 && !bstWriteBusy()) {
|
if(currentTime >= next20hzUpdateAt_1 && !bstWriteBusy()) {
|
||||||
if(sendCounter == 0)
|
if(sendCounter == 0)
|
||||||
writeRCChannelToBST();
|
writeRCChannelToBST();
|
||||||
else if(sendCounter == 1)
|
else if(sendCounter == 1)
|
||||||
|
@ -1516,7 +1514,7 @@ void taskBstMasterProcess(void)
|
||||||
sendCounter++;
|
sendCounter++;
|
||||||
if(sendCounter > 1)
|
if(sendCounter > 1)
|
||||||
sendCounter = 0;
|
sendCounter = 0;
|
||||||
next20hzUpdateAt_1 = now + UPDATE_AT_20HZ;
|
next20hzUpdateAt_1 = currentTime + UPDATE_AT_20HZ;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(sensors(SENSOR_GPS) && !bstWriteBusy())
|
if(sensors(SENSOR_GPS) && !bstWriteBusy())
|
||||||
|
@ -1527,7 +1525,7 @@ void taskBstMasterProcess(void)
|
||||||
stopMotors();
|
stopMotors();
|
||||||
systemReset();
|
systemReset();
|
||||||
}
|
}
|
||||||
resetBstChecker();
|
resetBstChecker(currentTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*************************************************************************************************/
|
/*************************************************************************************************/
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
|
|
||||||
void bstProcessInCommand(void);
|
void bstProcessInCommand(void);
|
||||||
void bstSlaveProcessInCommand(void);
|
void bstSlaveProcessInCommand(void);
|
||||||
void taskBstMasterProcess(void);
|
void taskBstMasterProcess(uint32_t currentTime);
|
||||||
|
|
||||||
bool writeGpsPositionPrameToBST(void);
|
bool writeGpsPositionPrameToBST(void);
|
||||||
bool writeRollPitchYawToBST(void);
|
bool writeRollPitchYawToBST(void);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue