From f683d9bb773214b3f331248016207902a43e66ae Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Tue, 28 Dec 2010 18:59:58 +0000 Subject: [PATCH] Added changing values to RcChannel test. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1325 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- .../examples/AP_RcChannel/AP_RcChannel.pde | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RcChannel/examples/AP_RcChannel/AP_RcChannel.pde b/libraries/AP_RcChannel/examples/AP_RcChannel/AP_RcChannel.pde index 0a51f9810e..d902ab7414 100644 --- a/libraries/AP_RcChannel/examples/AP_RcChannel/AP_RcChannel.pde +++ b/libraries/AP_RcChannel/examples/AP_RcChannel/AP_RcChannel.pde @@ -23,6 +23,9 @@ AP_EEPromVar pwmDeadZone(100,"RC1_PWMDEADZONE"); AP_Var filter(false,"RC1_FILTER"); AP_Var reverse(false,"RC1_REVERSE"); +float testPosition = 0; +uint16_t testPwm = 1500; + FastSerialPort0(Serial); AP_RcChannel rc[] = @@ -60,16 +63,22 @@ void loop() delay(2000); // set by pwm - rc[CH_1].setPwm(1500); + rc[CH_1].setPwm(testPwm); Serial.printf("\nrc[CH_1].setPwm(1500)\n"); Serial.printf("pwm: %d position: %f\n",rc[CH_1].getPwm(), rc[CH_1].getPosition()); delay(2000); // set by position - rc[CH_1].setPosition(-50); + rc[CH_1].setPosition(testPosition); Serial.printf("\nrc[CH_1].setPosition(-50))\n"); Serial.printf("pwm: %d position: %f\n",rc[CH_1].getPwm(), rc[CH_1].getPosition()); delay(2000); + + // update test value + testPosition += 10; + if (testPosition > 100) testPosition = -100; + testPwm += 100; + if (testPwm > 1800) testPosition = 1200; }