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

Changed behavior of PR #1233 and doc update

Stick channels only have AUTO and HOLD mode.
AUX channels only have SET and HOLD mode.
Added check to parameter in CLI.
Modified rx.md to reflect changes (and more).

+1 squashed commit:

- A cleaner approach for the same functionality

Basically addressing all comments from Hydra
This commit is contained in:
ProDrone 2015-08-25 21:47:49 +02:00
parent f7530df974
commit a46832fd85
5 changed files with 45 additions and 27 deletions

View file

@ -346,27 +346,29 @@ static uint16_t getRxfailValue(uint8_t channel)
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig->failsafe_channel_configurations[channel];
switch(channelFailsafeConfiguration->mode) {
default:
case RX_FAILSAFE_MODE_AUTO:
switch (channel) {
case ROLL:
case PITCH:
case YAW:
return rxConfig->midrc;
case THROTTLE:
if (feature(FEATURE_3D))
return rxConfig->midrc;
else
return rxConfig->rx_min_usec;
}
// fall though to HOLD if there's nothing specific to do.
/* no break */
default:
case RX_FAILSAFE_MODE_INVALID:
case RX_FAILSAFE_MODE_HOLD:
return rcData[channel];
case RX_FAILSAFE_MODE_SET:
return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step);
}
}
STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfiguration_t range)