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
@ -14,83 +14,99 @@
|
|||||||
class APM_PI {
|
class APM_PI {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/// Constructor for PI that saves its settings to EEPROM
|
/// Constructor for PI that saves its settings to EEPROM
|
||||||
///
|
///
|
||||||
/// @note PI must be named to avoid either multiple parameters with the
|
/// @note PI must be named to avoid either multiple parameters with the
|
||||||
/// same name, or an overly complex constructor.
|
/// same name, or an overly complex constructor.
|
||||||
///
|
///
|
||||||
/// @param initial_p Initial value for the P term.
|
/// @param initial_p Initial value for the P term.
|
||||||
/// @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;
|
||||||
_imax = initial_imax;
|
_imax = initial_imax;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Iterate the PI, return the new control value
|
/// Iterate the PI, return the new control value
|
||||||
///
|
///
|
||||||
/// Positive error produces positive output.
|
/// Positive error produces positive output.
|
||||||
///
|
///
|
||||||
/// @param error The measured error value
|
/// @param error The measured error value
|
||||||
/// @param dt The time delta in milliseconds (note
|
/// @param dt The time delta in milliseconds (note
|
||||||
/// that update interval cannot be more
|
/// that update interval cannot be more
|
||||||
/// than 65.535 seconds due to limited range
|
/// than 65.535 seconds due to limited range
|
||||||
/// of the data type).
|
/// of the data type).
|
||||||
/// @param scaler An arbitrary scale factor
|
/// @param scaler An arbitrary scale factor
|
||||||
///
|
///
|
||||||
/// @returns The updated control output.
|
/// @returns The updated control output.
|
||||||
///
|
///
|
||||||
//long get_pi(int32_t error, float dt);
|
//long get_pi(int32_t error, float dt);
|
||||||
int32_t get_pi(int32_t error, float dt);
|
int32_t get_pi(int32_t error, float dt);
|
||||||
int32_t get_p(int32_t error);
|
int32_t get_p(int32_t error);
|
||||||
int32_t get_i(int32_t error, float dt);
|
int32_t get_i(int32_t error, float dt);
|
||||||
|
|
||||||
|
|
||||||
/// Reset the PI integrator
|
/// Reset the PI integrator
|
||||||
///
|
///
|
||||||
void reset_I();
|
void reset_I();
|
||||||
|
|
||||||
/// Load gain properties
|
/// Load gain properties
|
||||||
///
|
///
|
||||||
void load_gains();
|
void load_gains();
|
||||||
|
|
||||||
/// Save gain properties
|
/// Save gain properties
|
||||||
///
|
///
|
||||||
void save_gains();
|
void save_gains();
|
||||||
|
|
||||||
/// @name parameter accessors
|
/// @name parameter accessors
|
||||||
//@{
|
//@{
|
||||||
|
|
||||||
/// 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[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Float _kp;
|
AP_Float _kp;
|
||||||
AP_Float _ki;
|
AP_Float _ki;
|
||||||
AP_Int16 _imax;
|
AP_Int16 _imax;
|
||||||
|
|
||||||
float _integrator; ///< integrator value
|
float _integrator; ///< integrator value
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user