mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AC_PID - added more paranoid checking that imax is positive in constructor, operator() and load_gains methods
This commit is contained in:
parent
aeb010b6e9
commit
f8ad719825
@ -120,6 +120,7 @@ AC_PID::load_gains()
|
||||
_ki.load();
|
||||
_kd.load();
|
||||
_imax.load();
|
||||
_imax = abs(_imax);
|
||||
}
|
||||
|
||||
void
|
||||
|
@ -33,7 +33,7 @@ public:
|
||||
_kp (initial_p),
|
||||
_ki (initial_i),
|
||||
_kd (initial_d),
|
||||
_imax(initial_imax)
|
||||
_imax(abs(initial_imax))
|
||||
{
|
||||
// no need for explicit load, assuming that the main code uses AP_Param::load_all.
|
||||
}
|
||||
@ -78,7 +78,7 @@ public:
|
||||
const float i,
|
||||
const float d,
|
||||
const int16_t imaxval) {
|
||||
_kp = p; _ki = i; _kd = d; _imax = imaxval;
|
||||
_kp = p; _ki = i; _kd = d; _imax = abs(imaxval);
|
||||
}
|
||||
|
||||
float kP() const { return _kp.get(); }
|
||||
|
Loading…
Reference in New Issue
Block a user