Skip to content

Commit

Permalink
SRV_Channel: allow re-assignment from GPIO on channels above 16
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
peterbarker committed Jan 8, 2025
1 parent 42cc456 commit 77bdea9
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/SRV_Channel/SRV_Channel_aux.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down

0 comments on commit 77bdea9

Please sign in to comment.