Fixed rc channel.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1850 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2011-04-06 01:19:03 +00:00
parent 81c5770b77
commit 5e726335fa
2 changed files with 3 additions and 5 deletions

View File

@ -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

View File

@ -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);