mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
uncrustify libraries/APM_PI/APM_PI.h
This commit is contained in:
parent
72dd47ee56
commit
0aaac4e7db
@ -23,9 +23,9 @@ public:
|
|||||||
/// @param initial_i Initial value for the I term.
|
/// @param initial_i Initial value for the I term.
|
||||||
/// @param initial_imax Initial value for the imax term.4
|
/// @param initial_imax Initial value for the imax term.4
|
||||||
///
|
///
|
||||||
APM_PI(const float &initial_p = 0.0,
|
APM_PI(const float & initial_p = 0.0,
|
||||||
const float &initial_i = 0.0,
|
const float & initial_i = 0.0,
|
||||||
const int16_t &initial_imax = 0.0)
|
const int16_t & initial_imax = 0.0)
|
||||||
{
|
{
|
||||||
_kp = initial_p;
|
_kp = initial_p;
|
||||||
_ki = initial_i;
|
_ki = initial_i;
|
||||||
@ -67,21 +67,37 @@ 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 int16_t imaxval) {
|
const int16_t imaxval) {
|
||||||
_kp = p; _ki = i; _imax = imaxval;
|
_kp = p; _ki = i; _imax = imaxval;
|
||||||
}
|
}
|
||||||
|
|
||||||
float kP() const { return _kp.get(); }
|
float kP() const {
|
||||||
float kI() const { return _ki.get(); }
|
return _kp.get();
|
||||||
int16_t imax() const { return _imax.get(); }
|
}
|
||||||
|
float kI() const {
|
||||||
|
return _ki.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 imax(const int16_t v) { _imax.set(abs(v)); }
|
}
|
||||||
float get_integrator() const { return _integrator; }
|
void kI(const float v) {
|
||||||
void set_integrator(float i) { _integrator = i; }
|
_ki.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;
|
||||||
|
}
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user