1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 09:45:37 +03:00

Fix rssi logging.

This commit is contained in:
Kevin 2018-09-20 12:19:19 +02:00
parent b057ce550d
commit 836417bce2
3 changed files with 7 additions and 1 deletions

View file

@ -448,7 +448,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
#endif #endif
case FLIGHT_LOG_FIELD_CONDITION_RSSI: case FLIGHT_LOG_FIELD_CONDITION_RSSI:
return rxConfig()->rssi_channel > 0 || featureIsEnabled(FEATURE_RSSI_ADC); return isRssiConfigured();
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME: case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
return blackboxConfig()->p_ratio != 1; return blackboxConfig()->p_ratio != 1;

View file

@ -697,3 +697,8 @@ uint16_t rxGetRefreshRate(void)
{ {
return rxRuntimeConfig.rxRefreshRate; return rxRuntimeConfig.rxRefreshRate;
} }
bool isRssiConfigured(void)
{
return rssiSource != RSSI_SOURCE_NONE;
}

View file

@ -166,6 +166,7 @@ void setRssiMsp(uint8_t newMspRssi);
void updateRSSI(timeUs_t currentTimeUs); void updateRSSI(timeUs_t currentTimeUs);
uint16_t getRssi(void); uint16_t getRssi(void);
uint8_t getRssiPercent(void); uint8_t getRssiPercent(void);
bool isRssiConfigured(void);
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig); void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig);