From d16659331f26f80e89783c76b2e77e0c36c5730f Mon Sep 17 00:00:00 2001 From: skyscraper Date: Sun, 8 May 2016 09:24:11 +0100 Subject: [PATCH] RC_Channel_aux: Rename static member functions Further to refactor of RC_Channel class which included adding get_xx set_xx methods, some methods names are now in conflict with those in the derived RC_Channel_aux class. To keep a uniform naming convention in RC_Channel where functions are most used and most numerous, the offending functions in RC_Channel__aux are renamed as follows RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step) --- libraries/RC_Channel/RC_Channel_aux.cpp | 86 ++++++++++++------------- libraries/RC_Channel/RC_Channel_aux.h | 4 +- 2 files changed, 45 insertions(+), 45 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 3f6cab7b51..aced4ef890 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -33,16 +33,16 @@ RC_Channel_aux::output_ch(void) case k_none: // disabled return; case k_manual: // manual - radio_out = radio_in; + set_radio_out(get_radio_in()); break; case k_rcin1 ... k_rcin16: // rc pass-thru - radio_out = hal.rcin->read(function-k_rcin1); + set_radio_out(hal.rcin->read(function-k_rcin1)); break; case k_motor1 ... k_motor8: // handled by AP_Motors::rc_write() return; } - hal.rcout->write(_ch_out, radio_out); + hal.rcout->write(_ch_out, get_radio_out()); } /* @@ -153,13 +153,13 @@ void RC_Channel_aux::enable_aux_servos() // trim value on startup for (uint8_t i = 0; i < RC_AUX_MAX_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(); - // see if it is a valid function - if (function < RC_Channel_aux::k_nr_aux_servo_functions) { - _aux_channels[i]->enable_out(); - } - } - } + 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 + if (function < RC_Channel_aux::k_nr_aux_servo_functions) { + _aux_channels[i]->enable_out(); + } + } + } } /* @@ -173,9 +173,9 @@ RC_Channel_aux::set_radio(RC_Channel_aux::Aux_servo_function_t function, int16_t } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - _aux_channels[i]->radio_out = constrain_int16(value,_aux_channels[i]->radio_min,_aux_channels[i]->radio_max); + _aux_channels[i]->set_radio_out(constrain_int16(value,_aux_channels[i]->get_radio_min(),_aux_channels[i]->get_radio_max())); _aux_channels[i]->output(); - } + } } } @@ -190,10 +190,10 @@ RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::Aux_servo_function_t function, } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - int16_t value2 = value - 1500 + _aux_channels[i]->radio_trim; - _aux_channels[i]->radio_out = constrain_int16(value2,_aux_channels[i]->radio_min,_aux_channels[i]->radio_max); + int16_t value2 = value - 1500 + _aux_channels[i]->get_radio_trim(); + _aux_channels[i]->set_radio_out(constrain_int16(value2,_aux_channels[i]->get_radio_min(),_aux_channels[i]->get_radio_max())); _aux_channels[i]->output(); - } + } } } @@ -202,18 +202,18 @@ RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::Aux_servo_function_t function, the given function type */ void -RC_Channel_aux::set_radio_trim(RC_Channel_aux::Aux_servo_function_t function) +RC_Channel_aux::set_trim_to_radio_in_for(RC_Channel_aux::Aux_servo_function_t function) { if (!function_assigned(function)) { return; } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - if (_aux_channels[i]->radio_in != 0) { - _aux_channels[i]->radio_trim = _aux_channels[i]->radio_in; - _aux_channels[i]->radio_trim.save(); - } - } + if (_aux_channels[i]->get_radio_in() != 0) { + _aux_channels[i]->set_radio_trim( _aux_channels[i]->get_radio_in()); + _aux_channels[i]->save_radio_trim(); + } + } } } @@ -228,9 +228,9 @@ RC_Channel_aux::set_radio_to_min(RC_Channel_aux::Aux_servo_function_t function) } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - _aux_channels[i]->radio_out = _aux_channels[i]->radio_min; + _aux_channels[i]->set_radio_out( _aux_channels[i]->get_radio_min()); _aux_channels[i]->output(); - } + } } } @@ -245,7 +245,7 @@ RC_Channel_aux::set_radio_to_max(RC_Channel_aux::Aux_servo_function_t function) } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - _aux_channels[i]->radio_out = _aux_channels[i]->radio_max; + _aux_channels[i]->set_radio_out(_aux_channels[i]->get_radio_max()); _aux_channels[i]->output(); } } @@ -262,9 +262,9 @@ RC_Channel_aux::set_radio_to_trim(RC_Channel_aux::Aux_servo_function_t function) } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - _aux_channels[i]->radio_out = _aux_channels[i]->radio_trim; + _aux_channels[i]->set_radio_out( _aux_channels[i]->get_radio_trim()); _aux_channels[i]->output(); - } + } } } @@ -279,14 +279,14 @@ RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::Aux_servo_function_t function, } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - if (do_input_output) { - _aux_channels[i]->input(); - } - _aux_channels[i]->radio_out = _aux_channels[i]->radio_in; - if (do_input_output) { - _aux_channels[i]->output(); - } - } + if (do_input_output) { + _aux_channels[i]->input(); + } + _aux_channels[i]->set_radio_out(_aux_channels[i]->get_radio_in()); + if (do_input_output) { + _aux_channels[i]->output(); + } + } } } @@ -294,17 +294,17 @@ RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::Aux_servo_function_t function, set servo_out and call calc_pwm() for a given function */ void -RC_Channel_aux::set_servo_out(RC_Channel_aux::Aux_servo_function_t function, int16_t value) +RC_Channel_aux::set_servo_out_for(RC_Channel_aux::Aux_servo_function_t function, int16_t value) { if (!function_assigned(function)) { return; } for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->function.get() == function) { - _aux_channels[i]->servo_out = value; - _aux_channels[i]->calc_pwm(); + _aux_channels[i]->set_servo_out(value); + _aux_channels[i]->calc_pwm(); _aux_channels[i]->output(); - } + } } } @@ -356,15 +356,15 @@ RC_Channel_aux::set_servo_limit(RC_Channel_aux::Aux_servo_function_t function, R RC_Channel_aux *ch = _aux_channels[i]; if (ch && ch->function.get() == function) { uint16_t pwm = ch->get_limit_pwm(limit); - ch->radio_out = pwm; + ch->set_radio_out(pwm); if (ch->function.get() == k_manual) { // in order for output_ch() to work for k_manual we // also have to override radio_in - ch->radio_in = pwm; + ch->set_radio_in(pwm); } if (ch->function.get() >= k_rcin1 && ch->function.get() <= k_rcin16) { // save for k_rcin* - ch->radio_in = pwm; + ch->set_radio_in(pwm); } } } @@ -379,7 +379,7 @@ RC_Channel_aux::function_assigned(RC_Channel_aux::Aux_servo_function_t function) if (function < k_nr_aux_servo_functions) { return (_function_mask & (1ULL<function.get() == function) { - _aux_channels[i]->servo_out = value; + _aux_channels[i]->set_servo_out(value); _aux_channels[i]->set_range(angle_min, angle_max); _aux_channels[i]->calc_pwm(); _aux_channels[i]->output(); diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h index 4adc14c7fa..959c25d6d0 100644 --- a/libraries/RC_Channel/RC_Channel_aux.h +++ b/libraries/RC_Channel/RC_Channel_aux.h @@ -108,7 +108,7 @@ public: static void set_radio_trimmed(Aux_servo_function_t function, int16_t value); // set and save the trim for a function channel to radio_in - static void set_radio_trim(Aux_servo_function_t function); + static void set_trim_to_radio_in_for(Aux_servo_function_t function); // set radio_out to radio_min static void set_radio_to_min(Aux_servo_function_t function); @@ -123,7 +123,7 @@ public: static void copy_radio_in_out(Aux_servo_function_t function, bool do_input_output=false); // set servo_out - static void set_servo_out(Aux_servo_function_t function, int16_t value); + static void set_servo_out_for(Aux_servo_function_t function, int16_t value); // setup failsafe for an auxillary channel function, by pwm static void set_servo_failsafe_pwm(RC_Channel_aux::Aux_servo_function_t function, uint16_t pwm);