mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
RC_Channel_aux: minor cleanups
remove unused enable_out_ch() and enable k_manual channels. This ensures k_manual channels used for bottle drop are initialised correctly to trim output
This commit is contained in:
parent
127117b640
commit
8620a036de
@ -18,26 +18,15 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = {
|
|||||||
|
|
||||||
static RC_Channel_aux *_aux_channels[7];
|
static RC_Channel_aux *_aux_channels[7];
|
||||||
|
|
||||||
/// enable_out_ch - enable the channel through APM_RC
|
|
||||||
void
|
|
||||||
RC_Channel_aux::enable_out_ch(unsigned char ch_nr)
|
|
||||||
{
|
|
||||||
// enable_out this channel if it assigned to a function
|
|
||||||
if( function != k_none ) {
|
|
||||||
_apm_rc->enable_out(ch_nr);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/// map a function to a servo channel and output it
|
/// map a function to a servo channel and output it
|
||||||
void
|
void
|
||||||
RC_Channel_aux::output_ch(unsigned char ch_nr)
|
RC_Channel_aux::output_ch(unsigned char ch_nr)
|
||||||
{
|
{
|
||||||
// take care or two corner cases
|
// take care of two corner cases
|
||||||
switch(function)
|
switch(function)
|
||||||
{
|
{
|
||||||
case k_none: // disabled
|
case k_none: // disabled
|
||||||
return;
|
return;
|
||||||
break;
|
|
||||||
case k_manual: // manual
|
case k_manual: // manual
|
||||||
radio_out = radio_in;
|
radio_out = radio_in;
|
||||||
break;
|
break;
|
||||||
@ -97,7 +86,8 @@ enable_aux_servos()
|
|||||||
if (_aux_channels[i]) {
|
if (_aux_channels[i]) {
|
||||||
RC_Channel_aux::Aux_servo_function_t function = (RC_Channel_aux::Aux_servo_function_t)_aux_channels[i]->function.get();
|
RC_Channel_aux::Aux_servo_function_t function = (RC_Channel_aux::Aux_servo_function_t)_aux_channels[i]->function.get();
|
||||||
// see if it is a valid function
|
// see if it is a valid function
|
||||||
if (function > RC_Channel_aux::k_none && function < RC_Channel_aux::k_nr_aux_servo_functions) {
|
if (function < RC_Channel_aux::k_nr_aux_servo_functions) {
|
||||||
|
_aux_channels[i]->radio_out = _aux_channels[i]->radio_trim;
|
||||||
_aux_channels[i]->enable_out();
|
_aux_channels[i]->enable_out();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -118,7 +108,6 @@ RC_Channel_aux::set_radio_trim(RC_Channel_aux::Aux_servo_function_t function)
|
|||||||
_aux_channels[i]->radio_trim.save();
|
_aux_channels[i]->radio_trim.save();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -46,8 +46,6 @@ public:
|
|||||||
|
|
||||||
AP_Int8 function; ///< see Aux_servo_function_t enum
|
AP_Int8 function; ///< see Aux_servo_function_t enum
|
||||||
|
|
||||||
void enable_out_ch(unsigned char ch_nr);
|
|
||||||
|
|
||||||
void output_ch(unsigned char ch_nr);
|
void output_ch(unsigned char ch_nr);
|
||||||
|
|
||||||
// set and save the trim for a function channel to radio_in
|
// set and save the trim for a function channel to radio_in
|
||||||
|
Loading…
Reference in New Issue
Block a user