mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
PID: params always use set method
This commit is contained in:
parent
338779d27d
commit
8618b085be
@ -63,7 +63,7 @@ public:
|
|||||||
const float i,
|
const float i,
|
||||||
const float d,
|
const float d,
|
||||||
const int16_t imaxval) {
|
const int16_t imaxval) {
|
||||||
_kp = p; _ki = i; _kd = d; _imax = imaxval;
|
_kp.set(p); _ki.set(i); _kd.set(d); _imax.set(imaxval);
|
||||||
}
|
}
|
||||||
|
|
||||||
float kP() const {
|
float kP() const {
|
||||||
|
Loading…
Reference in New Issue
Block a user