1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Fix RSSI_SCALE_DEFAULT to 100% @ 4095

This commit is contained in:
jflyper 2017-08-14 21:11:23 +09:00
parent 8995dcec0e
commit 30fc55ba09
2 changed files with 1 additions and 2 deletions

View file

@ -617,7 +617,6 @@ static void updateRSSIPWM(void)
}
#define RSSI_ADC_SAMPLE_COUNT 16
//#define RSSI_SCALE (0xFFF / 100.0f)
static void updateRSSIADC(timeUs_t currentTimeUs)
{

View file

@ -82,7 +82,7 @@ extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2
#define RSSI_SCALE_MIN 1
#define RSSI_SCALE_MAX 255
#define RSSI_SCALE_DEFAULT 30
#define RSSI_SCALE_DEFAULT (4095.0f / 100.0f + 0.5f) // 100% @ 4095
typedef enum {
RX_FAILSAFE_MODE_AUTO = 0,