Fix accessors, _RC

git-svn-id: https://arducopter.googlecode.com/svn/trunk@931 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2010-11-26 01:45:17 +00:00
parent 264cca6d24
commit dc40ee00ae
2 changed files with 10 additions and 9 deletions

View File

@ -21,7 +21,7 @@ PID::get_pid(long error, long dt, float scaler)
// discrete low pass filter, cuts out the // discrete low pass filter, cuts out the
// high frequency noise that can drive the controller crazy // high frequency noise that can drive the controller crazy
derivative = _last_derivative + derivative = _last_derivative +
((delta_time / (RC + delta_time)) * (derivative - _last_derivative)); ((delta_time / (_RC + delta_time)) * (derivative - _last_derivative));
// update state // update state
_last_error = error; _last_error = error;

View File

@ -67,14 +67,15 @@ public:
/// @name parameter accessors /// @name parameter accessors
//@{ //@{
float kP() { return _kp; } float kP() { return _kp; }
float &kP() { return _kp; } float kI() { return _ki; }
float kI() { return _ki; } float kD() { return _kd; }
float &kI() { return _kd; } float imax() { return _imax; }
float kD() { return _kd; }
float &kD() { return _kd; } void kP(float v) { _kp = v; }
float imax() { return _imax; } void kI(float v) { _ki = v; }
float &imax() { return _imax; } void kD(float v) { _kd = v; }
void imax(float v) { _imax = v; }
//@} //@}
private: private: