mirror of https://github.com/ArduPilot/ardupilot
AP_Param: update PID libraries for new constructor syntax
This commit is contained in:
parent
c298d5130f
commit
5e8fe8d93e
|
@ -7,10 +7,10 @@
|
|||
#include "AC_PID.h"
|
||||
|
||||
const AP_Param::GroupInfo AC_PID::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("P", 0, AC_PID, _kp),
|
||||
AP_GROUPINFO("I", 1, AC_PID, _ki),
|
||||
AP_GROUPINFO("D", 2, AC_PID, _kd),
|
||||
AP_GROUPINFO("IMAX", 3, AC_PID, _imax),
|
||||
AP_GROUPINFO("P", 0, AC_PID, _kp, 0),
|
||||
AP_GROUPINFO("I", 1, AC_PID, _ki, 0),
|
||||
AP_GROUPINFO("D", 2, AC_PID, _kd, 0),
|
||||
AP_GROUPINFO("IMAX", 3, AC_PID, _imax, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -28,14 +28,12 @@ public:
|
|||
const float &initial_p = 0.0,
|
||||
const float &initial_i = 0.0,
|
||||
const float &initial_d = 0.0,
|
||||
const int16_t &initial_imax = 0.0) :
|
||||
|
||||
_kp (initial_p),
|
||||
_ki (initial_i),
|
||||
_kd (initial_d),
|
||||
_imax(abs(initial_imax))
|
||||
const int16_t &initial_imax = 0.0)
|
||||
{
|
||||
// no need for explicit load, assuming that the main code uses AP_Param::load_all.
|
||||
_kp = initial_p;
|
||||
_ki = initial_i;
|
||||
_kd = initial_d;
|
||||
_imax = abs(initial_imax);
|
||||
}
|
||||
|
||||
/// Iterate the PID, return the new control value
|
||||
|
|
|
@ -8,9 +8,9 @@
|
|||
#include "APM_PI.h"
|
||||
|
||||
const AP_Param::GroupInfo APM_PI::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("P", 0, APM_PI, _kp),
|
||||
AP_GROUPINFO("I", 1, APM_PI, _ki),
|
||||
AP_GROUPINFO("IMAX", 2, APM_PI, _imax),
|
||||
AP_GROUPINFO("P", 0, APM_PI, _kp, 0),
|
||||
AP_GROUPINFO("I", 1, APM_PI, _ki, 0),
|
||||
AP_GROUPINFO("IMAX", 2, APM_PI, _imax, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -25,12 +25,11 @@ public:
|
|||
///
|
||||
APM_PI(const float &initial_p = 0.0,
|
||||
const float &initial_i = 0.0,
|
||||
const int16_t &initial_imax = 0.0) :
|
||||
_kp (initial_p),
|
||||
_ki (initial_i),
|
||||
_imax(initial_imax)
|
||||
const int16_t &initial_imax = 0.0)
|
||||
{
|
||||
// no need for explicit load, assuming that the main code uses AP_Var::load_all.
|
||||
_kp = initial_p;
|
||||
_ki = initial_i;
|
||||
_imax = initial_imax;
|
||||
}
|
||||
|
||||
/// Iterate the PI, return the new control value
|
||||
|
|
|
@ -8,10 +8,10 @@
|
|||
#include "PID.h"
|
||||
|
||||
const AP_Param::GroupInfo PID::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("P", 0, PID, _kp),
|
||||
AP_GROUPINFO("I", 1, PID, _ki),
|
||||
AP_GROUPINFO("D", 2, PID, _kd),
|
||||
AP_GROUPINFO("IMAX", 3, PID, _imax),
|
||||
AP_GROUPINFO("P", 0, PID, _kp, 0),
|
||||
AP_GROUPINFO("I", 1, PID, _ki, 0),
|
||||
AP_GROUPINFO("D", 2, PID, _kd, 0),
|
||||
AP_GROUPINFO("IMAX", 3, PID, _imax, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -17,12 +17,12 @@ public:
|
|||
PID(const float &initial_p = 0.0,
|
||||
const float &initial_i = 0.0,
|
||||
const float &initial_d = 0.0,
|
||||
const int16_t &initial_imax = 0) :
|
||||
_kp (initial_p),
|
||||
_ki (initial_i),
|
||||
_kd (initial_d),
|
||||
_imax(initial_imax)
|
||||
const int16_t &initial_imax = 0)
|
||||
{
|
||||
_kp = initial_p;
|
||||
_ki = initial_i;
|
||||
_kd = initial_d;
|
||||
_imax = initial_imax;
|
||||
}
|
||||
|
||||
/// Iterate the PID, return the new control value
|
||||
|
|
Loading…
Reference in New Issue