mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
Merge pull request #10097 from etracer65/rssi_channel_constrain_range
Fix underflow in channel based RSSI calculations for out of range values
This commit is contained in:
commit
66b7cc7c6a
1 changed files with 1 additions and 1 deletions
|
@ -757,7 +757,7 @@ static void updateRSSIPWM(void)
|
|||
int16_t pwmRssi = rcData[rxConfig()->rssi_channel - 1];
|
||||
|
||||
// Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
|
||||
setRssiDirect(scaleRange(pwmRssi, PWM_RANGE_MIN, PWM_RANGE_MAX, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_CHANNEL);
|
||||
setRssiDirect(scaleRange(constrain(pwmRssi, PWM_RANGE_MIN, PWM_RANGE_MAX), PWM_RANGE_MIN, PWM_RANGE_MAX, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_CHANNEL);
|
||||
}
|
||||
|
||||
static void updateRSSIADC(timeUs_t currentTimeUs)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue