Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SRV_Channels: find_channel: use channel mask remove need for search over all channels #27849

Merged
merged 1 commit into from
Aug 19, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 16 additions & 7 deletions libraries/SRV_Channel/SRV_Channel_aux.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -565,16 +565,25 @@ bool SRV_Channels::set_aux_channel_default(SRV_Channel::Aux_servo_function_t fun
// find first channel that a function is assigned to
bool SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
{
if (!function_assigned(function)) {
// Must have populated channel masks
if (!initialised) {
update_aux_servo_function();
}
Comment on lines +569 to +571
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We do this in several places, we really should not have too.... We could remove it and put in a SITL only panic.


// Make sure function is valid
if (!SRV_Channel::valid_function(function)) {
return false;
}
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
if (channels[i].function == function) {
chan = channels[i].ch_num;
return true;
}

// Get the index of the first set bit, returns 0 if no bits are set
const int first_chan = __builtin_ffs(functions[function].channel_mask);
if (first_chan == 0) {
return false;
}
return false;

// Convert to 0 indexed
chan = first_chan - 1;
return true;
}

/*
Expand Down
Loading