mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: add k_min, m_trim and k_max to output min/trim/max values
This commit is contained in:
parent
17f806cdb9
commit
3264fd750b
|
@ -158,6 +158,9 @@ public:
|
|||
k_ProfiLED_3 = 131,
|
||||
k_ProfiLED_Clock = 132,
|
||||
k_winch_clutch = 133,
|
||||
k_min = 134, // always outputs SERVOn_MIN
|
||||
k_trim = 135, // always outputs SERVOn_TRIM
|
||||
k_max = 136, // always outputs SERVOn_MAX
|
||||
k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one)
|
||||
} Aux_servo_function_t;
|
||||
|
||||
|
|
|
@ -197,6 +197,19 @@ void SRV_Channels::enable_aux_servos()
|
|||
hal.rcout->enable_ch(c.ch_num);
|
||||
}
|
||||
|
||||
// output some servo functions before we fiddle with the
|
||||
// parameter values:
|
||||
if (c.function.get() == SRV_Channel::k_min) {
|
||||
c.set_output_pwm(c.servo_min);
|
||||
c.output_ch();
|
||||
} else if (c.function.get() == SRV_Channel::k_trim) {
|
||||
c.set_output_pwm(c.servo_trim);
|
||||
c.output_ch();
|
||||
} else if (c.function.get() == SRV_Channel::k_max) {
|
||||
c.set_output_pwm(c.servo_max);
|
||||
c.output_ch();
|
||||
}
|
||||
|
||||
/*
|
||||
for channels which have been marked as digital output then the
|
||||
MIN/MAX/TRIM values have no meaning for controlling output, as
|
||||
|
|
Loading…
Reference in New Issue