uncrustify libraries/PID/PID.h

This commit is contained in:
uncrustify 2012-08-16 23:22:44 -07:00 committed by Pat Hickey
parent 330c6c07e3
commit 13e0dd2c70

View File

@ -14,10 +14,10 @@
class PID { class PID {
public: public:
PID(const float &initial_p = 0.0, PID(const float & initial_p = 0.0,
const float &initial_i = 0.0, const float & initial_i = 0.0,
const float &initial_d = 0.0, const float & initial_d = 0.0,
const int16_t &initial_imax = 0) const int16_t & initial_imax = 0)
{ {
_kp = initial_p; _kp = initial_p;
_ki = initial_i; _ki = initial_i;
@ -56,24 +56,42 @@ public:
//@{ //@{
/// Overload the function call operator to permit relatively easy initialisation /// 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 i,
const float d, const float d,
const int16_t imaxval) { const int16_t imaxval) {
_kp = p; _ki = i; _kd = d; _imax = imaxval; _kp = p; _ki = i; _kd = d; _imax = 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 {
return _integrator;
}
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];