mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Merge branch 'rc-calibration' of
https://github.com/digitalentity/cleanflight into digitalentity-rc-calibration Conflicts: docs/Rx.md src/main/io/serial_cli.c src/main/rx/rx.c src/main/rx/rx.h
This commit is contained in:
commit
27f8223de7
10 changed files with 300 additions and 5 deletions
|
@ -339,7 +339,20 @@ static uint16_t getRxfailValue(uint8_t channel)
|
|||
|
||||
}
|
||||
|
||||
static void processRxChannels(void)
|
||||
STATIC_UNIT_TESTED uint16_t applyRxCalibration(int sample, int minrc, int maxrc)
|
||||
{
|
||||
// Check special condition sample = PPM_RCVR_TIMEOUT, allow no signal value to avoid being corrupted by calibration
|
||||
if (sample == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
sample = scaleRange(sample, minrc, maxrc, PWM_RANGE_MIN, PWM_RANGE_MAX);
|
||||
sample = MIN(MAX(PWM_PULSE_MIN, sample), PWM_PULSE_MAX);
|
||||
|
||||
return sample;
|
||||
}
|
||||
|
||||
void processRxChannels(void)
|
||||
{
|
||||
uint8_t chan;
|
||||
|
||||
|
@ -361,6 +374,11 @@ static void processRxChannels(void)
|
|||
// sample the channel
|
||||
uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel);
|
||||
|
||||
// apply the rx calibration
|
||||
if (chan < MAX_CALIBRATED_RX_CHANNELS) {
|
||||
sample = applyRxCalibration(sample, rxConfig->calibration[chan].minrc, rxConfig->calibration[chan].maxrc);
|
||||
}
|
||||
|
||||
rxUpdateFlightChannelStatus(chan, sample);
|
||||
|
||||
if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue