mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 23:35:34 +03:00
Used currentTime parameter for beeper and telemetry
This commit is contained in:
parent
2f9ca4355c
commit
c600dc3784
9 changed files with 22 additions and 39 deletions
|
@ -855,7 +855,6 @@ void taskMainPidLoopCheck(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
UNUSED(currentTime);
|
UNUSED(currentTime);
|
||||||
|
|
||||||
static uint32_t previousTime;
|
|
||||||
static bool runTaskMainSubprocesses;
|
static bool runTaskMainSubprocesses;
|
||||||
static uint8_t pidUpdateCountdown;
|
static uint8_t pidUpdateCountdown;
|
||||||
|
|
||||||
|
@ -904,9 +903,7 @@ void taskHandleSerial(uint32_t currentTime)
|
||||||
|
|
||||||
void taskUpdateBeeper(uint32_t currentTime)
|
void taskUpdateBeeper(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
UNUSED(currentTime);
|
beeperUpdate(currentTime); //call periodic beeper handler
|
||||||
|
|
||||||
beeperUpdate(); //call periodic beeper handler
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateBattery(uint32_t currentTime)
|
void taskUpdateBattery(uint32_t currentTime)
|
||||||
|
@ -934,10 +931,8 @@ void taskUpdateBattery(uint32_t currentTime)
|
||||||
|
|
||||||
bool taskUpdateRxCheck(uint32_t currentTime, uint32_t currentDeltaTime)
|
bool taskUpdateRxCheck(uint32_t currentTime, uint32_t currentDeltaTime)
|
||||||
{
|
{
|
||||||
UNUSED(currentDeltaTime);
|
UNUSED(currentDeltaTime);
|
||||||
|
return rxUpdate(currentTime);
|
||||||
updateRx(currentTime);
|
|
||||||
return shouldProcessRx(currentTime);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskUpdateRxMain(uint32_t currentTime)
|
void taskUpdateRxMain(uint32_t currentTime)
|
||||||
|
@ -967,8 +962,6 @@ void taskUpdateRxMain(uint32_t currentTime)
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
void taskProcessGPS(uint32_t currentTime)
|
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
|
||||||
|
@ -997,7 +990,7 @@ void taskUpdateBaro(uint32_t currentTime)
|
||||||
UNUSED(currentTime);
|
UNUSED(currentTime);
|
||||||
|
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
uint32_t newDeadline = baroUpdate();
|
const uint32_t newDeadline = baroUpdate();
|
||||||
rescheduleTask(TASK_SELF, newDeadline);
|
rescheduleTask(TASK_SELF, newDeadline);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1041,12 +1034,10 @@ void taskUpdateDisplay(uint32_t currentTime)
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
void taskTelemetry(uint32_t currentTime)
|
void taskTelemetry(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
UNUSED(currentTime);
|
|
||||||
|
|
||||||
telemetryCheckState();
|
telemetryCheckState();
|
||||||
|
|
||||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||||
telemetryProcess(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
telemetryProcess(currentTime, &masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -283,7 +283,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(void)
|
void beeperUpdate(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
// 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)) {
|
||||||
|
@ -303,8 +303,7 @@ void beeperUpdate(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t now = millis();
|
if (beeperNextToggleTime > currentTime) {
|
||||||
if (beeperNextToggleTime > now) {
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -403,7 +402,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(void) {}
|
void beeperUpdate(uint32_t currentTime) {}
|
||||||
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;}
|
||||||
|
|
|
@ -47,7 +47,7 @@ typedef enum {
|
||||||
|
|
||||||
void beeper(beeperMode_e mode);
|
void beeper(beeperMode_e mode);
|
||||||
void beeperSilence(void);
|
void beeperSilence(void);
|
||||||
void beeperUpdate(void);
|
void beeperUpdate(uint32_t currentTime);
|
||||||
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);
|
||||||
|
|
|
@ -333,7 +333,7 @@ void resumeRxSignal(void)
|
||||||
failsafeOnRxResume();
|
failsafeOnRxResume();
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateRx(uint32_t currentTime)
|
bool rxUpdate(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
resetRxSignalReceivedFlagIfNeeded(currentTime);
|
resetRxSignalReceivedFlagIfNeeded(currentTime);
|
||||||
|
|
||||||
|
@ -384,11 +384,7 @@ void updateRx(uint32_t currentTime)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
return rxDataReceived || (currentTime >= rxUpdateAt); // data driven or 50Hz
|
||||||
|
|
||||||
bool shouldProcessRx(uint32_t currentTime)
|
|
||||||
{
|
|
||||||
return rxDataReceived || ((int32_t)(currentTime - rxUpdateAt) >= 0); // data driven or 50Hz
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
|
static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
|
||||||
|
|
|
@ -151,10 +151,9 @@ typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t
|
||||||
struct modeActivationCondition_s;
|
struct modeActivationCondition_s;
|
||||||
void rxInit(rxConfig_t *rxConfig, struct modeActivationCondition_s *modeActivationConditions);
|
void rxInit(rxConfig_t *rxConfig, struct modeActivationCondition_s *modeActivationConditions);
|
||||||
void useRxConfig(rxConfig_t *rxConfigToUse);
|
void useRxConfig(rxConfig_t *rxConfigToUse);
|
||||||
void updateRx(uint32_t currentTime);
|
bool rxUpdate(uint32_t currentTime);
|
||||||
bool rxIsReceivingSignal(void);
|
bool rxIsReceivingSignal(void);
|
||||||
bool rxAreFlightChannelsValid(void);
|
bool rxAreFlightChannelsValid(void);
|
||||||
bool shouldProcessRx(uint32_t currentTime);
|
|
||||||
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);
|
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);
|
||||||
|
|
||||||
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
|
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
|
||||||
|
|
|
@ -490,7 +490,7 @@ void checkHoTTTelemetryState(void)
|
||||||
freeHoTTTelemetryPort();
|
freeHoTTTelemetryPort();
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleHoTTTelemetry(void)
|
void handleHoTTTelemetry(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
static uint32_t serialTimer;
|
static uint32_t serialTimer;
|
||||||
|
|
||||||
|
@ -498,27 +498,25 @@ void handleHoTTTelemetry(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t now = micros();
|
if (shouldPrepareHoTTMessages(currentTime)) {
|
||||||
|
|
||||||
if (shouldPrepareHoTTMessages(now)) {
|
|
||||||
hottPrepareMessages();
|
hottPrepareMessages();
|
||||||
lastMessagesPreparedAt = now;
|
lastMessagesPreparedAt = currentTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (shouldCheckForHoTTRequest()) {
|
if (shouldCheckForHoTTRequest()) {
|
||||||
hottCheckSerialData(now);
|
hottCheckSerialData(currentTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!hottMsg)
|
if (!hottMsg)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
if (hottIsSending) {
|
if (hottIsSending) {
|
||||||
if(now - serialTimer < HOTT_TX_DELAY_US) {
|
if(currentTime - serialTimer < HOTT_TX_DELAY_US) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hottSendTelemetryData();
|
hottSendTelemetryData();
|
||||||
serialTimer = now;
|
serialTimer = currentTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -485,7 +485,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(void);
|
void handleHoTTTelemetry(uint32_t currentTime);
|
||||||
void checkHoTTTelemetryState(void);
|
void checkHoTTTelemetryState(void);
|
||||||
|
|
||||||
void initHoTTTelemetry(telemetryConfig_t *telemetryConfig);
|
void initHoTTTelemetry(telemetryConfig_t *telemetryConfig);
|
||||||
|
|
|
@ -90,10 +90,10 @@ void telemetryCheckState(void)
|
||||||
checkJetiExBusTelemetryState();
|
checkJetiExBusTelemetryState();
|
||||||
}
|
}
|
||||||
|
|
||||||
void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||||
{
|
{
|
||||||
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
||||||
handleHoTTTelemetry();
|
handleHoTTTelemetry(currentTime);
|
||||||
handleSmartPortTelemetry();
|
handleSmartPortTelemetry();
|
||||||
handleLtmTelemetry();
|
handleLtmTelemetry();
|
||||||
handleJetiExBusTelemetry();
|
handleJetiExBusTelemetry();
|
||||||
|
|
|
@ -53,7 +53,7 @@ extern serialPort_t *telemetrySharedPort;
|
||||||
|
|
||||||
void telemetryCheckState(void);
|
void telemetryCheckState(void);
|
||||||
struct rxConfig_s;
|
struct rxConfig_s;
|
||||||
void telemetryProcess(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
void telemetryProcess(uint32_t currentTime, struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||||
|
|
||||||
bool telemetryDetermineEnabledState(portSharing_e portSharing);
|
bool telemetryDetermineEnabledState(portSharing_e portSharing);
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue