From ce4547a1a5b92ec67f5fa72545bad1a533cb04b9 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Sun, 13 Nov 2011 14:18:14 +1100 Subject: [PATCH] purple: rework the RC_Channel library for the APM_RC changes --- libraries/RC_Channel/RC_Channel.cpp | 6 ++++++ libraries/RC_Channel/RC_Channel.h | 3 +++ libraries/RC_Channel/RC_Channel_aux.cpp | 2 +- 3 files changed, 10 insertions(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 96da440698..72577a7444 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -18,6 +18,7 @@ #define RC_CHANNEL_RANGE 1 #define RC_CHANNEL_ANGLE_RAW 2 +APM_RC_Class *RC_Channel::_apm_rc; // setup the control preferences void @@ -252,3 +253,8 @@ RC_Channel::norm_output() else return (float)(radio_out - radio_trim) / (float)(radio_max - radio_trim); } + +void RC_Channel::set_apm_rc( APM_RC_Class * apm_rc ) +{ + _apm_rc = apm_rc; +} diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 1bbe02fd58..8d473cbf79 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -7,6 +7,7 @@ #define RC_Channel_h #include +#include /// @class RC_Channel /// @brief Object managing one RC channel @@ -93,6 +94,8 @@ class RC_Channel{ int16_t range_to_pwm(); float scale_output; + static void set_apm_rc(APM_RC_Class * apm_rc); + static APM_RC_Class *_apm_rc; private: bool _filter; diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index bf73492351..fc2b2c9e39 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -56,7 +56,7 @@ RC_Channel_aux::output_ch(unsigned char ch_nr) break; } - APM_RC.OutputCh(ch_nr, radio_out); + _apm_rc->OutputCh(ch_nr, radio_out); } // Update the g_rc_function array of pointers to rc_x channels