Correct misunderstanding about the intent of the external gain array.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@978 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
14f500a688
commit
a64c5ef782
@ -8,6 +8,12 @@
|
|||||||
|
|
||||||
#include "PID.h"
|
#include "PID.h"
|
||||||
|
|
||||||
|
// make the gain array members a little easier to identify
|
||||||
|
#define _kp _gain_array[0]
|
||||||
|
#define _ki _gain_array[1]
|
||||||
|
#define _kd _gain_array[2]
|
||||||
|
#define _imax _gain_array[3]
|
||||||
|
|
||||||
long
|
long
|
||||||
PID::get_pid(int32_t error, uint16_t dt, float scaler)
|
PID::get_pid(int32_t error, uint16_t dt, float scaler)
|
||||||
{
|
{
|
||||||
@ -60,32 +66,24 @@ PID::imax(float v)
|
|||||||
void
|
void
|
||||||
PID::load_gains()
|
PID::load_gains()
|
||||||
{
|
{
|
||||||
if (_address) {
|
if ((_gain_array == &_local_gains[0]) && (_address)) {
|
||||||
_kp = (float)(eeprom_read_word((uint16_t *) _address)) / 1000.0;
|
_kp = (float)(eeprom_read_word((uint16_t *) _address)) / 1000.0;
|
||||||
_ki = (float)(eeprom_read_word((uint16_t *) (_address + 2))) / 1000.0;
|
_ki = (float)(eeprom_read_word((uint16_t *) (_address + 2))) / 1000.0;
|
||||||
_kd = (float)(eeprom_read_word((uint16_t *) (_address + 4))) / 1000.0;
|
_kd = (float)(eeprom_read_word((uint16_t *) (_address + 4))) / 1000.0;
|
||||||
_imax = eeprom_read_word((uint16_t *) (_address + 6)) * 100;
|
_imax = eeprom_read_word((uint16_t *) (_address + 6)) * 100;
|
||||||
} else {
|
|
||||||
_kp = _gain_array[0];
|
|
||||||
_ki = _gain_array[1];
|
|
||||||
_kd = _gain_array[2];
|
|
||||||
_imax = _gain_array[3];
|
|
||||||
}
|
}
|
||||||
|
// load is a NOP if the gain array is managed externally
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
PID::save_gains()
|
PID::save_gains()
|
||||||
{
|
{
|
||||||
if (_address) {
|
if ((_gain_array == &_local_gains[0]) && (_address)) {
|
||||||
eeprom_write_word((uint16_t *) _address, (int)(_kp * 1000));
|
eeprom_write_word((uint16_t *) _address, (int)(_kp * 1000));
|
||||||
eeprom_write_word((uint16_t *) (_address + 2), (int)(_ki * 1000));
|
eeprom_write_word((uint16_t *) (_address + 2), (int)(_ki * 1000));
|
||||||
eeprom_write_word((uint16_t *) (_address + 4), (int)(_kd * 1000));
|
eeprom_write_word((uint16_t *) (_address + 4), (int)(_kd * 1000));
|
||||||
eeprom_write_word((uint16_t *) (_address + 6), (int)_imax/100);
|
eeprom_write_word((uint16_t *) (_address + 6), (int)_imax/100);
|
||||||
} else {
|
|
||||||
_gain_array[0] = _kp;
|
|
||||||
_gain_array[1] = _ki;
|
|
||||||
_gain_array[2] = _kd;
|
|
||||||
_gain_array[3] = _imax;
|
|
||||||
}
|
}
|
||||||
|
// save is a NOP if the gain array is managed externally
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -15,30 +15,37 @@ public:
|
|||||||
/// Constructor
|
/// Constructor
|
||||||
///
|
///
|
||||||
/// A PID constructed in this fashion does not support save/restore.
|
/// A PID constructed in this fashion does not support save/restore.
|
||||||
|
/// Gains are managed internally, and must be read/written using the
|
||||||
|
/// accessor functions.
|
||||||
///
|
///
|
||||||
PID() :
|
PID() :
|
||||||
_address(0)
|
_address(0),
|
||||||
|
_gain_array(&_local_gains[0])
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
///
|
///
|
||||||
|
/// The PID will manage gains internally, and the load/save functions
|
||||||
|
/// will use 16 bytes of EEPROM storage to store gain values.
|
||||||
|
///
|
||||||
/// @param address EEPROM base address at which PID parameters
|
/// @param address EEPROM base address at which PID parameters
|
||||||
/// are stored. Zero if the PID does not support
|
/// are stored.
|
||||||
/// save/restore.
|
|
||||||
///
|
///
|
||||||
PID(uint16_t address) :
|
PID(uint16_t address) :
|
||||||
_address(address)
|
_address(address),
|
||||||
|
_gain_array(&_local_gains[0])
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
///
|
///
|
||||||
/// @param gain_array Address of an array of floats from which
|
/// Gain values for the PID are managed externally; load/save are a NOP.
|
||||||
/// gains will be loaded and to which they
|
///
|
||||||
/// are saved.
|
/// @param gain_array Address of an array of float values. The
|
||||||
|
/// array is used as kP, kI, kD and imax
|
||||||
|
/// respectively.
|
||||||
///
|
///
|
||||||
PID(float *gain_array) :
|
PID(float *gain_array) :
|
||||||
_gain_array(gain_array),
|
_gain_array(gain_array)
|
||||||
_address(0) // must init address to zero to have gain_array respected
|
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/// Iterate the PID, return the new control value
|
/// Iterate the PID, return the new control value
|
||||||
@ -74,29 +81,30 @@ public:
|
|||||||
|
|
||||||
/// @name parameter accessors
|
/// @name parameter accessors
|
||||||
//@{
|
//@{
|
||||||
float kP() { return _kp; }
|
float kP() { return _gain_array[0]; }
|
||||||
float kI() { return _ki; }
|
float kI() { return _gain_array[1]; }
|
||||||
float kD() { return _kd; }
|
float kD() { return _gain_array[2]; }
|
||||||
float imax() { return _imax; }
|
float imax() { return _gain_array[3]; }
|
||||||
|
|
||||||
void kP(float v) { _kp = v; }
|
void kP(const float v) { _gain_array[0] = v; }
|
||||||
void kI(float v) { _ki = v; }
|
void kI(const float v) { _gain_array[1] = v; }
|
||||||
void kD(float v) { _kd = v; }
|
void kD(const float v) { _gain_array[2] = v; }
|
||||||
void imax(float v);
|
void imax(const float v);
|
||||||
|
|
||||||
|
// one-shot operator for setting all of the gain properties at once
|
||||||
|
void operator ()(const float p, const float i, const float d, const float max)
|
||||||
|
{ kP(p); kI(i); kD(d); imax(max); }
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint16_t _address; ///< EEPROM address for save/restore of P/I/D
|
uint16_t _address; ///< EEPROM address for save/restore of P/I/D
|
||||||
float *_gain_array; ///< pointer to the gains for this pid
|
float *_gain_array; ///< pointer to the gains for this pid
|
||||||
|
|
||||||
float _kp; ///< proportional gain
|
float _local_gains[4]; ///< local storage for gains when not globally managed
|
||||||
float _ki; ///< integral gain
|
|
||||||
float _kd; ///< derivative gain
|
|
||||||
float _imax; ///< integrator magnitude clamp
|
|
||||||
|
|
||||||
float _integrator; ///< integrator value
|
float _integrator; ///< integrator value
|
||||||
int32_t _last_error; ///< last error for derivative
|
int32_t _last_error; ///< last error for derivative
|
||||||
float _last_derivative; ///< last derivative for low-pass filter
|
float _last_derivative; ///< last derivative for low-pass filter
|
||||||
|
|
||||||
/// Low pass filter cut frequency for derivative calculation.
|
/// Low pass filter cut frequency for derivative calculation.
|
||||||
///
|
///
|
||||||
|
Loading…
Reference in New Issue
Block a user