From 5e726335fa5ab00376293901cb1b8418aa107fcb Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Wed, 6 Apr 2011 01:19:03 +0000 Subject: [PATCH] Fixed rc channel. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1850 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_RcChannel/AP_RcChannel.cpp | 6 ++---- libraries/AP_RcChannel/AP_RcChannel.h | 2 +- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/libraries/AP_RcChannel/AP_RcChannel.cpp b/libraries/AP_RcChannel/AP_RcChannel.cpp index 1d0fef3bfb..689d8ab230 100644 --- a/libraries/AP_RcChannel/AP_RcChannel.cpp +++ b/libraries/AP_RcChannel/AP_RcChannel.cpp @@ -37,10 +37,8 @@ AP_RcChannel::AP_RcChannel(AP_Var::Key key, const prog_char_t * name, APM_RC_Cla } -void AP_RcChannel::readRadio() { - // apply reverse - uint16_t pwmRadio = _rc.InputCh(ch); - setPwm(pwmRadio); +uint16_t AP_RcChannel::readRadio() { + return _rc.InputCh(ch); } void diff --git a/libraries/AP_RcChannel/AP_RcChannel.h b/libraries/AP_RcChannel/AP_RcChannel.h index 9b0522f669..5729c91cfd 100644 --- a/libraries/AP_RcChannel/AP_RcChannel.h +++ b/libraries/AP_RcChannel/AP_RcChannel.h @@ -37,7 +37,7 @@ public: AP_Bool reverse; // set - void readRadio(); + uint16_t readRadio(); void setPwm(uint16_t pwm); void setPosition(float position); void setNormalized(float normPosition);