mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
uncrustify libraries/PID/PID.h
This commit is contained in:
parent
330c6c07e3
commit
13e0dd2c70
@ -63,17 +63,35 @@ public:
|
||||
_kp = p; _ki = i; _kd = d; _imax = imaxval;
|
||||
}
|
||||
|
||||
float kP() const { return _kp.get(); }
|
||||
float kI() const { return _ki.get(); }
|
||||
float kD() const { return _kd.get(); }
|
||||
int16_t imax() const { return _imax.get(); }
|
||||
float kP() const {
|
||||
return _kp.get();
|
||||
}
|
||||
float kI() const {
|
||||
return _ki.get();
|
||||
}
|
||||
float kD() const {
|
||||
return _kd.get();
|
||||
}
|
||||
int16_t imax() const {
|
||||
return _imax.get();
|
||||
}
|
||||
|
||||
void kP(const float v) { _kp.set(v); }
|
||||
void kI(const float v) { _ki.set(v); }
|
||||
void kD(const float v) { _kd.set(v); }
|
||||
void imax(const int16_t v) { _imax.set(abs(v)); }
|
||||
void kP(const float v) {
|
||||
_kp.set(v);
|
||||
}
|
||||
void kI(const float v) {
|
||||
_ki.set(v);
|
||||
}
|
||||
void kD(const float v) {
|
||||
_kd.set(v);
|
||||
}
|
||||
void imax(const int16_t v) {
|
||||
_imax.set(abs(v));
|
||||
}
|
||||
|
||||
float get_integrator() const { return _integrator; }
|
||||
float get_integrator() const {
|
||||
return _integrator;
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user