mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
convert APM_PI library to AP_Param
This commit is contained in:
parent
74e0d2ef2a
commit
170fdef857
@ -7,6 +7,13 @@
|
||||
|
||||
#include "APM_PI.h"
|
||||
|
||||
const AP_Param::GroupInfo APM_PI::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("P", APM_PI, _kp),
|
||||
AP_GROUPINFO("I", APM_PI, _ki),
|
||||
AP_GROUPINFO("IMAX", APM_PI, _imax),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
int32_t APM_PI::get_p(int32_t error)
|
||||
{
|
||||
return (float)error * _kp;
|
||||
@ -40,11 +47,15 @@ APM_PI::reset_I()
|
||||
void
|
||||
APM_PI::load_gains()
|
||||
{
|
||||
_group.load();
|
||||
_kp.load();
|
||||
_ki.load();
|
||||
_imax.load();
|
||||
}
|
||||
|
||||
void
|
||||
APM_PI::save_gains()
|
||||
{
|
||||
_group.save();
|
||||
_kp.save();
|
||||
_ki.save();
|
||||
_imax.save();
|
||||
}
|
||||
|
@ -19,51 +19,20 @@ public:
|
||||
/// @note PI must be named to avoid either multiple parameters with the
|
||||
/// same name, or an overly complex constructor.
|
||||
///
|
||||
/// @param key Storage key assigned to this PI. Should be unique.
|
||||
/// @param name Name by which the PI is known, or NULL for an anonymous PI.
|
||||
/// The name is prefixed to the P, I, IMAX variable names when
|
||||
/// they are reported.
|
||||
/// @param initial_p Initial value for the P term.
|
||||
/// @param initial_i Initial value for the I term.
|
||||
/// @param initial_imax Initial value for the imax term.4
|
||||
///
|
||||
APM_PI(AP_Var::Key key,
|
||||
const prog_char_t *name,
|
||||
const float &initial_p = 0.0,
|
||||
const float &initial_i = 0.0,
|
||||
const int16_t &initial_imax = 0.0) :
|
||||
|
||||
_group(key, name),
|
||||
// group, index, initial value, name
|
||||
_kp (&_group, 0, initial_p, PSTR("P")),
|
||||
_ki (&_group, 1, initial_i, PSTR("I")),
|
||||
_imax(&_group, 3, initial_imax, PSTR("IMAX"))
|
||||
APM_PI(const float &initial_p = 0.0,
|
||||
const float &initial_i = 0.0,
|
||||
const int16_t &initial_imax = 0.0) :
|
||||
_kp (initial_p),
|
||||
_ki (initial_i),
|
||||
_imax(initial_imax)
|
||||
{
|
||||
// no need for explicit load, assuming that the main code uses AP_Var::load_all.
|
||||
}
|
||||
|
||||
/// Constructor for PI that does not save its settings.
|
||||
///
|
||||
/// @param name Name by which the PI is known, or NULL for an anonymous PI.
|
||||
/// The name is prefixed to the P, I, IMAX variable names when
|
||||
/// they are reported.
|
||||
/// @param initial_p Initial value for the P term.
|
||||
/// @param initial_i Initial value for the I term.
|
||||
/// @param initial_imax Initial value for the imax term.4
|
||||
///
|
||||
APM_PI(const prog_char_t *name,
|
||||
const float &initial_p = 0.0,
|
||||
const float &initial_i = 0.0,
|
||||
const int16_t &initial_imax = 0.0) :
|
||||
|
||||
_group(AP_Var::k_key_none, name),
|
||||
// group, index, initial value, name
|
||||
_kp (&_group, 0, initial_p, PSTR("P")),
|
||||
_ki (&_group, 1, initial_i, PSTR("I")),
|
||||
_imax(&_group, 3, initial_imax, PSTR("IMAX"))
|
||||
{
|
||||
}
|
||||
|
||||
/// Iterate the PI, return the new control value
|
||||
///
|
||||
/// Positive error produces positive output.
|
||||
@ -115,10 +84,11 @@ public:
|
||||
float get_integrator() const { return _integrator; }
|
||||
void set_integrator(float i) { _integrator = i; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_Var_group _group;
|
||||
AP_Float16 _kp;
|
||||
AP_Float16 _ki;
|
||||
AP_Float _kp;
|
||||
AP_Float _ki;
|
||||
AP_Int16 _imax;
|
||||
|
||||
float _integrator; ///< integrator value
|
||||
|
Loading…
Reference in New Issue
Block a user