From 11f196318e9f39e9c56f6fd69b5ef812f63c8abe Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Apr 2014 12:18:56 +1100 Subject: [PATCH] RC_Channel: added static functions to simplify operations on all channels this avoids vehicle code having to loop over all channels for common operations --- libraries/RC_Channel/RC_Channel.cpp | 22 ++++++++++++++++++++++ libraries/RC_Channel/RC_Channel.h | 2 ++ libraries/RC_Channel/RC_Channel_aux.cpp | 17 +++++++++++++++-- libraries/RC_Channel/RC_Channel_aux.h | 6 +++++- 4 files changed, 44 insertions(+), 3 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index a44b2adcf6..9164f4a60b 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -160,6 +160,19 @@ RC_Channel::set_pwm(int16_t pwm) } } +/* + call read() and set_pwm() on all channels + */ +void +RC_Channel::set_pwm_all(void) +{ + for (uint8_t i=0; iset_pwm(rc_ch[i]->read()); + } + } +} + // read input from APM_RC - create a control_in value, but use a // zero value for the dead zone. When done this way the control_in // value can be used as servo_out to give the same output as input @@ -388,6 +401,15 @@ void RC_Channel::output_trim() const hal.rcout->write(_ch_out, radio_trim); } +void RC_Channel::output_trim_all() +{ + for (uint8_t i=0; ioutput_trim(); + } + } +} + void RC_Channel::input() { diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index a5caf7b8ed..8f619fdb69 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -53,6 +53,7 @@ public: // read input from APM_RC - create a control_in value void set_pwm(int16_t pwm); + static void set_pwm_all(void); void set_pwm_no_deadzone(int16_t pwm); // pwm is stored here @@ -98,6 +99,7 @@ public: void output() const; void output_trim() const; + static void output_trim_all(); uint16_t read() const; void input(); void enable_out(); diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index b9100a7bf2..2594867eaa 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -24,7 +24,7 @@ uint32_t RC_Channel_aux::_function_mask; /// map a function to a servo channel and output it void -RC_Channel_aux::output_ch(unsigned char ch_nr) +RC_Channel_aux::output_ch(void) { // take care of two corner cases switch(function) @@ -35,7 +35,20 @@ RC_Channel_aux::output_ch(unsigned char ch_nr) radio_out = radio_in; break; } - hal.rcout->write(ch_nr, radio_out); + hal.rcout->write(_ch_out, radio_out); +} + +/* + call output_ch() on all auxillary channels + */ +void +RC_Channel_aux::output_ch_all(void) +{ + for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { + if (_aux_channels[i]) { + _aux_channels[i]->output_ch(); + } + } } /* diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h index 9f54bd9655..7b3302581b 100644 --- a/libraries/RC_Channel/RC_Channel_aux.h +++ b/libraries/RC_Channel/RC_Channel_aux.h @@ -71,7 +71,11 @@ public: AP_Int8 function; ///< see Aux_servo_function_t enum - void output_ch(unsigned char ch_nr); + // output one auxillary channel + void output_ch(void); + + // output all auxillary channels + static void output_ch_all(void); // set radio_out for a function channel static void set_radio(Aux_servo_function_t function, int16_t value);