mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_PID: save 8 bytes per AC_PID object
we don't need the _derivative or _output variables
This commit is contained in:
parent
1dad9e4e94
commit
eac1ad49d6
@ -55,19 +55,19 @@ int32_t AC_PID::get_leaky_i(int32_t error, float dt, float leak_rate)
|
||||
int32_t AC_PID::get_d(int32_t input, float dt)
|
||||
{
|
||||
if ((_kd != 0) && (dt != 0)) {
|
||||
_derivative = (input - _last_input) / dt;
|
||||
float derivative = (input - _last_input) / dt;
|
||||
|
||||
// discrete low pass filter, cuts out the
|
||||
// high frequency noise that can drive the controller crazy
|
||||
_derivative = _last_derivative +
|
||||
(dt / ( _filter + dt)) * (_derivative - _last_derivative);
|
||||
derivative = _last_derivative +
|
||||
(dt / ( _filter + dt)) * (derivative - _last_derivative);
|
||||
|
||||
// update state
|
||||
_last_input = input;
|
||||
_last_derivative = _derivative;
|
||||
_last_derivative = derivative;
|
||||
|
||||
// add in derivative component
|
||||
return _kd * _derivative;
|
||||
return _kd * derivative;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@ -83,47 +83,6 @@ int32_t AC_PID::get_pid(int32_t error, float dt)
|
||||
return get_p(error) + get_i(error, dt) + get_d(error, dt);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
* int32_t AC_PID::get_pid(int32_t error, float dt)
|
||||
* {
|
||||
* // Compute proportional component
|
||||
* _output = error * _kp;
|
||||
*
|
||||
* // Compute derivative component if time has elapsed
|
||||
* if ((fabs(_kd) > 0) && (dt > 0)) {
|
||||
* _derivative = (error - _last_error) / dt;
|
||||
*
|
||||
* // discrete low pass filter, cuts out the
|
||||
* // high frequency noise that can drive the controller crazy
|
||||
* _derivative = _last_derivative +
|
||||
* (dt / ( _filter + dt)) * (_derivative - _last_derivative);
|
||||
*
|
||||
* // update state
|
||||
* _last_error = error;
|
||||
* _last_derivative = _derivative;
|
||||
*
|
||||
* // add in derivative component
|
||||
* _output += _kd * _derivative;
|
||||
* }
|
||||
*
|
||||
* // Compute integral component if time has elapsed
|
||||
* if ((fabs(_ki) > 0) && (dt > 0)) {
|
||||
* _integrator += (error * _ki) * dt;
|
||||
* if (_integrator < -_imax) {
|
||||
* _integrator = -_imax;
|
||||
* } else if (_integrator > _imax) {
|
||||
* _integrator = _imax;
|
||||
* }
|
||||
* _output += _integrator;
|
||||
* }
|
||||
*
|
||||
* return _output;
|
||||
* }
|
||||
*/
|
||||
|
||||
|
||||
void
|
||||
AC_PID::reset_I()
|
||||
{
|
||||
|
@ -124,8 +124,6 @@ private:
|
||||
float _integrator; ///< integrator value
|
||||
int32_t _last_input; ///< last input for derivative
|
||||
float _last_derivative; ///< last derivative for low-pass filter
|
||||
float _output;
|
||||
float _derivative;
|
||||
|
||||
/// Low pass filter cut frequency for derivative calculation.
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user