mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
SRV_Channel: allow re-assignment from GPIO on channels above 16
this allows MotorMatrix to change a channel's default (and value) from k_GPIO to a motor output value. The loop in the SRV_Channels contructors sets all defaults for channels above 16 to GPIO, and this code stopped MotorsMatrix from assigning a different role the the output.
This commit is contained in:
parent
49d9b14e25
commit
9f5c095688
@ -544,7 +544,8 @@ bool SRV_Channels::set_aux_channel_default(SRV_Channel::Aux_servo_function_t fun
|
||||
// already assigned
|
||||
return true;
|
||||
}
|
||||
if (channels[channel].function != SRV_Channel::k_none) {
|
||||
if (channels[channel].function != SRV_Channel::k_none &&
|
||||
!(channel >15 && channels[channel].function == SRV_Channel::k_GPIO)) {
|
||||
if (channels[channel].function == function) {
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user