From 49619b15dd7259a08ef059c225c04b98b9a5f764 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 9 Dec 2012 16:42:58 +0900 Subject: [PATCH] RC_Channel: move RC_CHANNEL_ANGLE, RANGE, ANGLE_RAW type definitions to .h file so they can be used by the main sketch --- libraries/RC_Channel/RC_Channel.cpp | 18 +++++++----------- libraries/RC_Channel/RC_Channel.h | 4 ++++ 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index cc4d2c25bc..66d4d420b1 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -19,10 +19,6 @@ #endif #include "RC_Channel.h" -#define RC_CHANNEL_ANGLE 0 -#define RC_CHANNEL_RANGE 1 -#define RC_CHANNEL_ANGLE_RAW 2 - /// global array with pointers to all APM RC channels, will be used by AP_Mount and AP_Camera classes /// It points to RC input channels, both APM1 and APM2 only have 8 input channels. RC_Channel* rc_ch[NUM_CHANNELS]; @@ -76,7 +72,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { void RC_Channel::set_range(int16_t low, int16_t high) { - _type = RC_CHANNEL_RANGE; + _type = RC_CHANNEL_TYPE_RANGE; _high = high; _low = low; _high_out = high; @@ -93,7 +89,7 @@ RC_Channel::set_range_out(int16_t low, int16_t high) void RC_Channel::set_angle(int16_t angle) { - _type = RC_CHANNEL_ANGLE; + _type = RC_CHANNEL_TYPE_ANGLE; _high = angle; } @@ -136,14 +132,14 @@ RC_Channel::set_pwm(int16_t pwm) { radio_in = pwm; - if(_type == RC_CHANNEL_RANGE) { + if(_type == RC_CHANNEL_TYPE_RANGE) { control_in = pwm_to_range(); //control_in = constrain(control_in, _low, _high); //control_in = min(control_in, _high); control_in = (control_in < _dead_zone) ? 0 : control_in; } else { - //RC_CHANNEL_ANGLE, RC_CHANNEL_ANGLE_RAW + //RC_CHANNEL_TYPE_ANGLE, RC_CHANNEL_TYPE_ANGLE_RAW control_in = pwm_to_angle(); } } @@ -165,15 +161,15 @@ RC_Channel::get_failsafe(void) void RC_Channel::calc_pwm(void) { - if(_type == RC_CHANNEL_RANGE) { + if(_type == RC_CHANNEL_TYPE_RANGE) { pwm_out = range_to_pwm(); radio_out = (_reverse >= 0) ? (radio_min + pwm_out) : (radio_max - pwm_out); - }else if(_type == RC_CHANNEL_ANGLE_RAW) { + }else if(_type == RC_CHANNEL_TYPE_ANGLE_RAW) { pwm_out = (float)servo_out * .1; radio_out = (pwm_out * _reverse) + radio_trim; - }else{ // RC_CHANNEL_ANGLE + }else{ // RC_CHANNEL_TYPE_ANGLE pwm_out = angle_to_pwm(); radio_out = pwm_out + radio_trim; } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index e457df9301..e941cf0154 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -9,6 +9,10 @@ #include #include +#define RC_CHANNEL_TYPE_ANGLE 0 +#define RC_CHANNEL_TYPE_RANGE 1 +#define RC_CHANNEL_TYPE_ANGLE_RAW 2 + /// @class RC_Channel /// @brief Object managing one RC channel class RC_Channel {