purple: rework the RC_Channel library for the APM_RC changes

This commit is contained in:
Pat Hickey 2011-11-13 14:18:14 +11:00
parent f36ded2854
commit c9f7618ccc
3 changed files with 10 additions and 1 deletions

View File

@ -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;
}

View File

@ -7,6 +7,7 @@
#define RC_Channel_h
#include <AP_Common.h>
#include <APM_RC.h>
/// @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;

View File

@ -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