mirror of https://github.com/ArduPilot/ardupilot
Fix accessors, _RC
git-svn-id: https://arducopter.googlecode.com/svn/trunk@931 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
264cca6d24
commit
dc40ee00ae
|
@ -21,7 +21,7 @@ PID::get_pid(long error, long dt, float scaler)
|
|||
// discrete low pass filter, cuts out the
|
||||
// high frequency noise that can drive the controller crazy
|
||||
derivative = _last_derivative +
|
||||
((delta_time / (RC + delta_time)) * (derivative - _last_derivative));
|
||||
((delta_time / (_RC + delta_time)) * (derivative - _last_derivative));
|
||||
|
||||
// update state
|
||||
_last_error = error;
|
||||
|
|
|
@ -67,14 +67,15 @@ public:
|
|||
|
||||
/// @name parameter accessors
|
||||
//@{
|
||||
float kP() { return _kp; }
|
||||
float &kP() { return _kp; }
|
||||
float kI() { return _ki; }
|
||||
float &kI() { return _kd; }
|
||||
float kD() { return _kd; }
|
||||
float &kD() { return _kd; }
|
||||
float imax() { return _imax; }
|
||||
float &imax() { return _imax; }
|
||||
float kP() { return _kp; }
|
||||
float kI() { return _ki; }
|
||||
float kD() { return _kd; }
|
||||
float imax() { return _imax; }
|
||||
|
||||
void kP(float v) { _kp = v; }
|
||||
void kI(float v) { _ki = v; }
|
||||
void kD(float v) { _kd = v; }
|
||||
void imax(float v) { _imax = v; }
|
||||
//@}
|
||||
|
||||
private:
|
||||
|
|
Loading…
Reference in New Issue