mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: remove unused defualt in get channel for function
This commit is contained in:
parent
9077f60e87
commit
4785c248c5
@ -481,7 +481,7 @@ public:
|
||||
static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan);
|
||||
|
||||
// find first channel that a function is assigned to, returning SRV_Channel object
|
||||
static SRV_Channel *get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1);
|
||||
static SRV_Channel *get_channel_for(SRV_Channel::Aux_servo_function_t function);
|
||||
|
||||
// call set_angle() on matching channels
|
||||
static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle);
|
||||
|
@ -559,12 +559,9 @@ bool SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t function, uint
|
||||
/*
|
||||
get a pointer to first auxiliary channel for a channel function
|
||||
*/
|
||||
SRV_Channel *SRV_Channels::get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan)
|
||||
SRV_Channel *SRV_Channels::get_channel_for(SRV_Channel::Aux_servo_function_t function)
|
||||
{
|
||||
uint8_t chan;
|
||||
if (default_chan >= 0) {
|
||||
set_aux_channel_default(function, default_chan);
|
||||
}
|
||||
if (!find_channel(function, chan)) {
|
||||
return nullptr;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user