mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Fixed rxfail and rxrange CLI commands
This commit is contained in:
parent
dcecf9dc67
commit
0b100bf167
7 changed files with 43 additions and 43 deletions
|
@ -1816,8 +1816,8 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
case MSP_SET_RXFAIL_CONFIG:
|
||||
i = sbufReadU8(src);
|
||||
if (i < MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
||||
rxConfigMutable()->failsafe_channel_configurations[i].mode = sbufReadU8(src);
|
||||
rxConfigMutable()->failsafe_channel_configurations[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
|
||||
rxFailsafeChannelConfigsMutable(i)->mode = sbufReadU8(src);
|
||||
rxFailsafeChannelConfigsMutable(i)->step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue