mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 06:45:16 +03:00
Provide temporary support for old clients that try and send a channel
index instead of a servo middle when using MSP_SET_SERVO_CONF. Old GUI clients can still be used to SET channel forwarding, but cannot be used to READ the status of channel forwarding until they are updated to use MSP_CHANNEL_FORWARDING/MSP_SET_CHANNEL_FORWARDING. To the user it will mean their GUI may not match the stored configuration. However there is no way to DISABLE channel forwarding other than a reset if they have enabled it using an old client. This situation is not ideal, but without this commit it would mean that bad data could be stored and used incorrectly by baseflight if a user enables channel forwarding using an old client.
This commit is contained in:
parent
3c1b0b1998
commit
799844d933
1 changed files with 8 additions and 1 deletions
|
@ -435,7 +435,14 @@ static void evaluateCommand(void)
|
|||
for (i = 0; i < MAX_SERVOS; i++) {
|
||||
cfg.servoConf[i].min = read16();
|
||||
cfg.servoConf[i].max = read16();
|
||||
cfg.servoConf[i].middle = read16();
|
||||
// provide temporary support for old clients that try and send a channel index instead of a servo middle
|
||||
uint16_t potentialServoMiddleOrChannelToForward = read16();
|
||||
if (potentialServoMiddleOrChannelToForward < MAX_SERVOS) {
|
||||
cfg.servoConf[i].forwardFromChannel = potentialServoMiddleOrChannelToForward;
|
||||
}
|
||||
if (potentialServoMiddleOrChannelToForward >= PWM_RANGE_MIN && potentialServoMiddleOrChannelToForward <= PWM_RANGE_MAX) {
|
||||
cfg.servoConf[i].middle = potentialServoMiddleOrChannelToForward;
|
||||
}
|
||||
cfg.servoConf[i].rate = read8();
|
||||
}
|
||||
break;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue