Added new output type AMGLE_RAW - this will ouput non-scaled PWM, better for copters than fixed wings.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2093 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-05 17:46:11 +00:00
parent 063d6a1e9a
commit 88a8c1113c
2 changed files with 18 additions and 7 deletions

View File

@ -14,14 +14,15 @@
#include "WProgram.h" #include "WProgram.h"
#include "RC_Channel.h" #include "RC_Channel.h"
#define ANGLE 0 #define RC_CHANNEL_ANGLE 0
#define RANGE 1 #define RC_CHANNEL_RANGE 1
#define RC_CHANNEL_ANGLE_RAW 2
// setup the control preferences // setup the control preferences
void void
RC_Channel::set_range(int low, int high) RC_Channel::set_range(int low, int high)
{ {
_type = RANGE; _type = RC_CHANNEL_RANGE;
_high = high; _high = high;
_low = low; _low = low;
} }
@ -29,7 +30,7 @@ RC_Channel::set_range(int low, int high)
void void
RC_Channel::set_angle(int angle) RC_Channel::set_angle(int angle)
{ {
_type = ANGLE; _type = RC_CHANNEL_ANGLE;
_high = angle; _high = angle;
} }
@ -52,6 +53,11 @@ RC_Channel::set_filter(bool filter)
{ {
_filter = filter; _filter = filter;
} }
void
RC_Channel::set_type(uint8_t t)
{
_type = t;
}
// call after first read // call after first read
void void
@ -75,7 +81,7 @@ RC_Channel::set_pwm(int pwm)
radio_in = pwm; radio_in = pwm;
} }
if(_type == RANGE){ if(_type == RC_CHANNEL_RANGE){
//Serial.print("range "); //Serial.print("range ");
control_in = pwm_to_range(); control_in = pwm_to_range();
control_in = (control_in < dead_zone) ? 0 : control_in; control_in = (control_in < dead_zone) ? 0 : control_in;
@ -109,10 +115,14 @@ RC_Channel::get_failsafe(void)
void void
RC_Channel::calc_pwm(void) RC_Channel::calc_pwm(void)
{ {
if(_type == RC_CHANNEL_RANGE){
if(_type == RANGE){
pwm_out = range_to_pwm(); pwm_out = range_to_pwm();
radio_out = pwm_out + radio_min; radio_out = pwm_out + radio_min;
}else if(_type == RC_CHANNEL_ANGLE_RAW){
pwm_out = (float)servo_out * .1;
radio_out = pwm_out + 1500;
}else{ }else{
pwm_out = angle_to_pwm(); pwm_out = angle_to_pwm();
radio_out = pwm_out + radio_trim; radio_out = pwm_out + radio_trim;

View File

@ -42,6 +42,7 @@ class RC_Channel{
void save_eeprom(void); void save_eeprom(void);
void save_trim(void); void save_trim(void);
void set_filter(bool filter); void set_filter(bool filter);
void set_type(uint8_t t);
// setup the control preferences // setup the control preferences
void set_range(int low, int high); void set_range(int low, int high);