From 77bdea93de164ab61ac5793c747e4e9ec6ebcc4f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Jan 2025 10:22:47 +1100 Subject: [PATCH] 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. --- libraries/SRV_Channel/SRV_Channel_aux.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 3fb4e922744d7..a08be42da3ad5 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -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; }