almost ready for use, still testing
git-svn-id: https://arducopter.googlecode.com/svn/trunk@905 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
4fa2491adf
commit
2dd479ea62
@ -27,7 +27,7 @@ RC_Channel::set_radio_range(int r_min, int r_max)
|
||||
|
||||
// setup the control preferences
|
||||
void
|
||||
RC_Channel::set_range(int high, int low)
|
||||
RC_Channel::set_range(int low, int high)
|
||||
{
|
||||
_type = RANGE;
|
||||
_high = high;
|
||||
@ -51,13 +51,16 @@ RC_Channel::set_trim(int pwm)
|
||||
// read input from APM_RC - create a control_in value
|
||||
void
|
||||
RC_Channel::set_pwm(int pwm)
|
||||
{
|
||||
{
|
||||
//Serial.print(pwm,DEC);
|
||||
|
||||
if(_radio_in == 0)
|
||||
_radio_in = pwm;
|
||||
else
|
||||
_radio_in = ((pwm + _radio_in) >> 1); // Small filtering
|
||||
|
||||
if(_type == RANGE){
|
||||
//Serial.print("range ");
|
||||
control_in = pwm_to_range();
|
||||
}else{
|
||||
control_in = pwm_to_angle();
|
||||
|
@ -21,7 +21,7 @@ class RC_Channel
|
||||
void set_radio_range(int r_min, int r_max);
|
||||
|
||||
// setup the control preferences
|
||||
void set_range(int high, int low);
|
||||
void set_range(int low, int high);
|
||||
void set_angle(int angle);
|
||||
|
||||
// call after first read
|
||||
|
@ -22,6 +22,7 @@ void setup()
|
||||
{
|
||||
Serial.begin(38400);
|
||||
Serial.println("ArduPilot RC Channel test");
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
|
||||
delay(1000);
|
||||
// setup radio
|
||||
@ -53,6 +54,7 @@ void loop()
|
||||
rc_2.set_pwm(APM_RC.InputCh(CH_2));
|
||||
rc_3.set_pwm(APM_RC.InputCh(CH_3));
|
||||
rc_4.set_pwm(APM_RC.InputCh(CH_4));
|
||||
|
||||
print_pwm();
|
||||
}
|
||||
|
||||
@ -65,5 +67,5 @@ void print_pwm()
|
||||
Serial.print("\tch3 :");
|
||||
Serial.print(rc_3.control_in, DEC);
|
||||
Serial.print("\tch4 :");
|
||||
Serial.print(rc_4.control_in, DEC);
|
||||
Serial.println(rc_4.control_in, DEC);
|
||||
}
|
Loading…
Reference in New Issue
Block a user