SRV_Channel: remove unused set_output_pwm_first method

This commit is contained in:
Peter Barker 2020-08-31 11:46:43 +10:00 committed by Andrew Tridgell
parent 629f2153e0
commit 5c2b478feb
2 changed files with 0 additions and 14 deletions

View File

@ -322,9 +322,6 @@ public:
// set output value for a function channel as a pwm value
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value);
// set output value for a function channel as a pwm value on the first matching channel
static void set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t value);
// set output value for a specific function channel as a pwm value
static void set_output_pwm_chan(uint8_t chan, uint16_t value);

View File

@ -633,17 +633,6 @@ void SRV_Channels::set_output_to_trim(SRV_Channel::Aux_servo_function_t function
}
}
// set output pwm to for first matching channel
void SRV_Channels::set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
{
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
if (channels[i].function == function) {
channels[i].set_output_pwm(pwm);
break;
}
}
}
/*
get the normalised output for a channel function from the pwm value
of the first matching channel