mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_PID: expose parameters as AP_Float
this enables full tuning capability
This commit is contained in:
parent
dbe9091d58
commit
412dc10353
@ -57,7 +57,7 @@ public:
|
||||
void operator() (const float p) { _kp = p; }
|
||||
|
||||
// accessors
|
||||
float kP() const { return _kp.get(); }
|
||||
AP_Float &kP() { return _kp; }
|
||||
void kP(const float v) { _kp.set(v); }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
@ -57,9 +57,9 @@ public:
|
||||
void operator() (float p, float i, float d, float imaxval, float input_filt_hz, float dt );
|
||||
|
||||
// get accessors
|
||||
float kP() const { return _kp.get(); }
|
||||
float kI() const { return _ki.get(); }
|
||||
float kD() const { return _kd.get(); }
|
||||
AP_Float &kP() { return _kp; }
|
||||
AP_Float &kI() { return _ki; }
|
||||
AP_Float &kD() { return _kd; }
|
||||
float imax() const { return _imax.get(); }
|
||||
float filt_hz() const { return _filt_hz.get(); }
|
||||
float get_filt_alpha() const;
|
||||
|
@ -51,8 +51,8 @@ public:
|
||||
void operator() (float p, float i, float imaxval, float input_filt_hz, float dt);
|
||||
|
||||
// get accessors
|
||||
float kP() const { return _kp.get(); }
|
||||
float kI() const { return _ki.get(); }
|
||||
AP_Float &kP() { return _kp; }
|
||||
AP_Float &kI() { return _ki; }
|
||||
float imax() const { return _imax.get(); }
|
||||
float filt_hz() const { return _filt_hz.get(); }
|
||||
float get_filt_alpha() const { return _filt_alpha; }
|
||||
|
Loading…
Reference in New Issue
Block a user