mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: added get_output_channel_mask()
will be used by AP_Motors
This commit is contained in:
parent
aeb2a628c4
commit
39fd25bb36
|
@ -278,6 +278,9 @@ public:
|
|||
// return zero on error.
|
||||
static float get_output_norm(SRV_Channel::Aux_servo_function_t function);
|
||||
|
||||
// get output channel mask for a function
|
||||
static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function);
|
||||
|
||||
// limit slew rate to given limit in percent per second
|
||||
static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt);
|
||||
|
||||
|
|
|
@ -460,6 +460,18 @@ int16_t SRV_Channels::get_output_scaled(SRV_Channel::Aux_servo_function_t functi
|
|||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
get mask of output channels for a function
|
||||
*/
|
||||
uint16_t SRV_Channels::get_output_channel_mask(SRV_Channel::Aux_servo_function_t function)
|
||||
{
|
||||
if (function < SRV_Channel::k_nr_aux_servo_functions) {
|
||||
return functions[function].channel_mask;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
// set the trim for a function channel to given pwm
|
||||
void SRV_Channels::set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm)
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue