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

Removed issue with sparse 'defaultAdjustmentConfigs' in adjustment ranges.

This commit is contained in:
mikeller 2018-11-11 00:44:20 +13:00
parent b58e8f827f
commit bc09e929b5
4 changed files with 10 additions and 10 deletions

View file

@ -974,7 +974,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
sbufWriteU8(dst, adjRange->auxChannelIndex);
sbufWriteU8(dst, adjRange->range.startStep);
sbufWriteU8(dst, adjRange->range.endStep);
sbufWriteU8(dst, adjRange->adjustmentFunction);
sbufWriteU8(dst, adjRange->adjustmentConfig);
sbufWriteU8(dst, adjRange->auxSwitchChannelIndex);
}
break;
@ -1623,7 +1623,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
adjRange->auxChannelIndex = sbufReadU8(src);
adjRange->range.startStep = sbufReadU8(src);
adjRange->range.endStep = sbufReadU8(src);
adjRange->adjustmentFunction = sbufReadU8(src);
adjRange->adjustmentConfig = sbufReadU8(src);
adjRange->auxSwitchChannelIndex = sbufReadU8(src);
} else {
return MSP_RESULT_ERROR;