Cleanup of AP_RcChannel, removed scaled class.

This commit is contained in:
James Goppert 2011-10-03 13:22:23 -04:00
parent 0fc595d528
commit cd451b749e
2 changed files with 11 additions and 25 deletions

View File

@ -20,12 +20,13 @@ namespace apo {
AP_RcChannel::AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, AP_RcChannel::AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name,
APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin, APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax, const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode, const bool & reverse) : const rcMode_t & rcMode, const bool & reverse, const float & scale) :
AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")), AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")),
_pwmMin(this, 2, pwmMin, PSTR("pMin")), _pwmMin(this, 2, pwmMin, PSTR("pMin")),
_pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")), _pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")),
_pwmMax(this, 4, pwmMax, PSTR("pMax")), _pwmMax(this, 4, pwmMax, PSTR("pMax")),
_reverse(this, 5, reverse, PSTR("rev")), _reverse(this, 5, reverse, PSTR("rev")),
_scale(scale == 0 ? AP_Float(0) : AP_Float(this,6,reverse,PSTR("scale"))),
_rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) { _rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) {
//Serial.print("pwm after ctor: "); Serial.println(pwmNeutral); //Serial.print("pwm after ctor: "); Serial.println(pwmNeutral);
if (rcMode == RC_MODE_IN) if (rcMode == RC_MODE_IN)

View File

@ -28,16 +28,16 @@ public:
const uint8_t & ch, const uint16_t & pwmMin, const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax, const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode, const rcMode_t & rcMode,
const bool & reverse); const bool & reverse, const float & scale = 0);
// configuration // configuration
AP_Uint8 _ch; AP_Uint8 _ch;
AP_Uint16 _pwmMin; AP_Uint16 _pwmMin;
AP_Uint16 _pwmNeutral; AP_Uint16 _pwmNeutral;
AP_Uint16 _pwmMax; AP_Uint16 _pwmMax;
AP_Uint8 _deg2mPwm;
rcMode_t _rcMode; rcMode_t _rcMode;
AP_Bool _reverse; AP_Bool _reverse;
AP_Float _scale;
// get // get
uint16_t getPwm() { uint16_t getPwm() {
@ -50,6 +50,9 @@ public:
float getRadioPosition() { float getRadioPosition() {
return _pwmToPosition(getRadioPwm()); return _pwmToPosition(getRadioPwm());
} }
float getScaled() {
return _scale*getPwm();
}
// set // set
void setUsingRadio() { void setUsingRadio() {
@ -59,7 +62,10 @@ public:
void setPosition(float position) { void setPosition(float position) {
setPwm(_positionToPwm(position)); setPwm(_positionToPwm(position));
} }
void setScaled(float val) {
setPwm(val/_scale);
}
protected: protected:
// configuration // configuration
@ -73,27 +79,6 @@ protected:
float _pwmToPosition(const uint16_t & pwm); float _pwmToPosition(const uint16_t & pwm);
}; };
class AP_RcChannel_Scaled : public AP_RcChannel {
public:
AP_RcChannel_Scaled(AP_Var::Key keyValue, const prog_char_t * name, APM_RC_Class & rc,
const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode,
const bool & reverse,
const float & scale) :
AP_RcChannel(keyValue,name,rc,ch,pwmMin,pwmNeutral,pwmMax,rcMode,reverse),
_scale(this, 6, pwmNeutral, PSTR("scale"))
{
}
AP_Float _scale;
void setScaled(float val) {
setPwm(val/_scale);
}
float getScaled() {
return _scale*getPwm();
}
};
} // apo } // apo
#endif // AP_RCCHANNEL_H #endif // AP_RCCHANNEL_H