mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
uncrustify libraries/AC_PID/AC_PID.h
This commit is contained in:
parent
66ab46fa88
commit
7aea7dc825
50
libraries/AC_PID/AC_PID.h
Executable file → Normal file
50
libraries/AC_PID/AC_PID.h
Executable file → Normal file
@ -25,10 +25,10 @@ public:
|
||||
/// @param initial_imax Initial value for the imax term.4
|
||||
///
|
||||
AC_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.0)
|
||||
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;
|
||||
@ -72,25 +72,45 @@ public:
|
||||
//@{
|
||||
|
||||
/// Overload the function call operator to permit relatively easy initialisation
|
||||
void operator() (const float p,
|
||||
void operator () (const float p,
|
||||
const float i,
|
||||
const float d,
|
||||
const int16_t imaxval) {
|
||||
_kp = p; _ki = i; _kd = d; _imax = abs(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; }
|
||||
void set_integrator(float i) { _integrator = i; }
|
||||
float get_integrator() const {
|
||||
return _integrator;
|
||||
}
|
||||
void set_integrator(float i) {
|
||||
_integrator = i;
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user