mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
uncrustify libraries/AC_PID/AC_PID.h
This commit is contained in:
parent
66ab46fa88
commit
7aea7dc825
40
libraries/AC_PID/AC_PID.h
Executable file → Normal file
40
libraries/AC_PID/AC_PID.h
Executable file → Normal file
@ -79,18 +79,38 @@ public:
|
|||||||
_kp = p; _ki = i; _kd = d; _imax = abs(imaxval);
|
_kp = p; _ki = i; _kd = d; _imax = abs(imaxval);
|
||||||
}
|
}
|
||||||
|
|
||||||
float kP() const { return _kp.get(); }
|
float kP() const {
|
||||||
float kI() const { return _ki.get(); }
|
return _kp.get();
|
||||||
float kD() const { return _kd.get(); }
|
}
|
||||||
int16_t imax() const { return _imax.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 kP(const float v) {
|
||||||
void kI(const float v) { _ki.set(v); }
|
_kp.set(v);
|
||||||
void kD(const float v) { _kd.set(v); }
|
}
|
||||||
void imax(const int16_t v) { _imax.set(abs(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 {
|
||||||
void set_integrator(float i) { _integrator = i; }
|
return _integrator;
|
||||||
|
}
|
||||||
|
void set_integrator(float i) {
|
||||||
|
_integrator = i;
|
||||||
|
}
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user