mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: added set_output_pwm_chan()
This commit is contained in:
parent
b541949262
commit
ce87bb7e39
|
@ -225,6 +225,9 @@ public:
|
|||
// 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);
|
||||
|
||||
// set output value for a function channel as a scaled value. This
|
||||
// calls calc_pwm() to also set the pwm value
|
||||
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value);
|
||||
|
|
|
@ -176,3 +176,11 @@ void SRV_Channels::calc_pwm(void)
|
|||
channels[i].calc_pwm(functions[channels[i].function].output_scaled);
|
||||
}
|
||||
}
|
||||
|
||||
// set output value for a specific function channel as a pwm value
|
||||
void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value)
|
||||
{
|
||||
if (chan < NUM_SERVO_CHANNELS) {
|
||||
channels[chan].set_output_pwm(value);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue