2013-08-29 02:34:34 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
2018-12-20 19:39:38 -04:00
2013-08-29 02:34:34 -03:00
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
2018-12-20 19:39:38 -04:00
2013-08-29 02:34:34 -03:00
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2012-08-21 23:08:14 -03:00
// Code by Jon Challinger
2013-04-23 08:02:18 -03:00
// Modified by Paul Riseborough
2012-08-21 23:08:14 -03:00
//
2015-08-11 03:28:41 -03:00
# include <AP_HAL/AP_HAL.h>
2012-08-21 23:08:14 -03:00
# include "AP_RollController.h"
2012-10-12 14:53:42 -03:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_RollController : : var_info [ ] = {
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_TCONST
2013-09-08 21:17:21 -03:00
// @DisplayName: Roll Time Constant
2018-12-20 19:39:38 -04:00
// @Description: Time constant in seconds from demanded to achieved roll angle. Most models respond well to 0.5. May be reduced for faster responses, but setting lower than a model can achieve will not help.
2013-05-13 08:10:55 -03:00
// @Range: 0.4 1.0
2017-05-02 10:39:35 -03:00
// @Units: s
2013-05-05 03:25:17 -03:00
// @Increment: 0.1
// @User: Advanced
2020-09-18 21:29:41 -03:00
AP_GROUPINFO ( " 2SRV_TCONST " , 0 , AP_RollController , gains . tau , 0.5f ) ,
2013-05-05 03:25:17 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_P
2013-05-13 08:10:55 -03:00
// @DisplayName: Proportional Gain
2018-12-20 19:39:38 -04:00
// @Description: Proportional gain from roll angle demands to ailerons. Higher values allow more servo response but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
2014-08-16 05:07:13 -03:00
// @Range: 0.1 4.0
2013-05-05 03:25:17 -03:00
// @Increment: 0.1
2020-09-18 21:29:41 -03:00
// @User: Standard
AP_GROUPINFO ( " 2SRV_P " , 1 , AP_RollController , gains . P , 1.0f ) ,
2013-05-05 03:25:17 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_D
2013-05-13 08:10:55 -03:00
// @DisplayName: Damping Gain
2018-12-20 19:39:38 -04:00
// @Description: Damping gain from roll acceleration to ailerons. Higher values reduce rolling in turbulence, but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
// @Range: 0 0.2
2013-05-05 03:25:17 -03:00
// @Increment: 0.01
2020-09-18 21:29:41 -03:00
// @User: Standard
AP_GROUPINFO ( " 2SRV_D " , 2 , AP_RollController , gains . D , 0.08f ) ,
2013-05-05 03:25:17 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_I
2013-05-13 08:10:55 -03:00
// @DisplayName: Integrator Gain
2018-12-20 19:39:38 -04:00
// @Description: Integrator gain from long-term roll angle offsets to ailerons. Higher values "trim" out offsets faster but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
2013-05-13 08:10:55 -03:00
// @Range: 0 1.0
// @Increment: 0.05
2020-09-18 21:29:41 -03:00
// @User: Standard
AP_GROUPINFO ( " 2SRV_I " , 3 , AP_RollController , gains . I , 0.3f ) ,
2013-05-05 03:25:17 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_RMAX
2013-05-13 08:10:55 -03:00
// @DisplayName: Maximum Roll Rate
2018-12-20 19:39:38 -04:00
// @Description: Maximum roll rate that the roll controller demands (degrees/sec) in ACRO mode.
2013-05-05 03:25:17 -03:00
// @Range: 0 180
2017-05-02 10:39:35 -03:00
// @Units: deg/s
2013-05-05 03:25:17 -03:00
// @Increment: 1
2013-05-13 08:10:55 -03:00
// @User: Advanced
2020-09-18 21:29:41 -03:00
AP_GROUPINFO ( " 2SRV_RMAX " , 4 , AP_RollController , gains . rmax , 0 ) ,
2013-05-05 03:25:17 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_IMAX
2013-06-11 05:35:31 -03:00
// @DisplayName: Integrator limit
2018-12-20 19:39:38 -04:00
// @Description: Limit of roll integrator gain in centi-degrees of servo travel. Servos are assumed to have +/- 4500 centi-degrees of travel, so a value of 3000 allows trim of up to 2/3 of servo travel range.
2013-06-11 05:35:31 -03:00
// @Range: 0 4500
// @Increment: 1
// @User: Advanced
2020-09-18 21:29:41 -03:00
AP_GROUPINFO ( " 2SRV_IMAX " , 5 , AP_RollController , gains . imax , 3000 ) ,
2013-06-11 05:35:31 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_FF
2015-05-23 00:26:17 -03:00
// @DisplayName: Feed forward Gain
2018-12-20 19:39:38 -04:00
// @Description: Gain from demanded rate to aileron output.
2015-05-23 00:26:17 -03:00
// @Range: 0.1 4.0
// @Increment: 0.1
2020-09-18 21:29:41 -03:00
// @User: Standard
AP_GROUPINFO ( " 2SRV_FF " , 6 , AP_RollController , gains . FF , 0.0f ) ,
2015-05-23 00:26:17 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_SRMAX
2020-05-10 04:11:11 -03:00
// @DisplayName: Servo slew rate limit
// @Description: Sets an upper limit on the servo slew rate produced by the D-gain (roll rate feedback). If the amplitude of the control action produced by the roll rate feedback exceeds this value, then the D-gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive D-gain. The parameter should be set to no more than 25% of the servo's specified slew rate to allow for inertia and aerodynamic load effects. Note: The D-gain will not be reduced to less than 10% of the nominal value. A valule of zero will disable this feature.
// @Units: deg/s
// @Range: 0 500
// @Increment: 10.0
// @User: Advanced
2020-09-18 21:29:41 -03:00
AP_GROUPINFO ( " 2SRV_SRMAX " , 7 , AP_RollController , _slew_rate_max , 150.0f ) ,
2020-05-10 04:11:11 -03:00
2020-09-18 21:29:41 -03:00
// @Param: 2SRV_SRTAU
2020-05-10 04:11:11 -03:00
// @DisplayName: Servo slew rate decay time constant
// @Description: This sets the time constant used to recover the D-gain after it has been reduced due to excessive servo slew rate.
// @Units: s
// @Range: 0.5 5.0
// @Increment: 0.1
// @User: Advanced
2020-09-18 21:29:41 -03:00
AP_GROUPINFO ( " 2SRV_SRTAU " , 8 , AP_RollController , _slew_rate_tau , 1.0f ) ,
2020-05-10 04:11:11 -03:00
2020-09-18 21:29:41 -03:00
// @Param: _RATE_P
// @DisplayName: Roll axis rate controller P gain
// @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
// @Range: 0.08 0.35
// @Increment: 0.005
// @User: Standard
// @Param: _RATE_I
// @DisplayName: Roll axis rate controller I gain
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
// @Range: 0.01 0.6
// @Increment: 0.01
// @User: Standard
// @Param: _RATE_IMAX
// @DisplayName: Roll axis rate controller I gain maximum
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard
// @Param: _RATE_D
// @DisplayName: Roll axis rate controller D gain
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
// @Range: 0.001 0.03
// @Increment: 0.001
// @User: Standard
// @Param: _RATE_FF
// @DisplayName: Roll axis rate controller feed forward
// @Description: Roll axis rate controller feed forward
// @Range: 0 3.0
// @Increment: 0.001
// @User: Standard
// @Param: _RATE_FLTT
// @DisplayName: Roll axis rate controller target frequency in Hz
// @Description: Roll axis rate controller target frequency in Hz
// @Range: 2 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: _RATE_FLTE
// @DisplayName: Roll axis rate controller error frequency in Hz
// @Description: Roll axis rate controller error frequency in Hz
// @Range: 2 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: _RATE_FLTD
// @DisplayName: Roll axis rate controller derivative frequency in Hz
// @Description: Roll axis rate controller derivative frequency in Hz
// @Range: 0 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: _RATE_SMAX
// @DisplayName: Roll slew rate limit
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
// @Param: _RATE_STAU
// @DisplayName: Roll slew rate decay time constant
// @Description: This sets the time constant used to recover the P+D gain after it has been reduced due to excessive slew rate.
// @Units: s
// @Range: 0.5 5.0
// @Increment: 0.1
// @User: Advanced
AP_SUBGROUPINFO ( rate_pid , " _RATE_ " , 9 , AP_RollController , AC_PID ) ,
2020-05-10 04:11:11 -03:00
AP_GROUPEND
2012-08-21 23:08:14 -03:00
} ;
2013-07-10 10:25:06 -03:00
/*
internal rate controller , called by attitude and rate controller
public functions
*/
2020-09-18 21:29:41 -03:00
int32_t AP_RollController : : _get_rate_out_old ( float desired_rate , float scaler , bool disable_integrator )
2012-08-21 23:08:14 -03:00
{
2015-11-19 23:05:52 -04:00
uint32_t tnow = AP_HAL : : millis ( ) ;
2012-08-21 23:08:14 -03:00
uint32_t dt = tnow - _last_t ;
if ( _last_t = = 0 | | dt > 1000 ) {
dt = 0 ;
}
_last_t = tnow ;
2013-07-20 01:37:05 -03:00
// Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
// No conversion is required for K_D
2014-04-12 01:11:33 -03:00
float ki_rate = gains . I * gains . tau ;
2015-05-23 00:26:17 -03:00
float eas2tas = _ahrs . get_EAS2TAS ( ) ;
2015-11-27 13:11:58 -04:00
float kp_ff = MAX ( ( gains . P - gains . I * gains . tau ) * gains . tau - gains . D , 0 ) / eas2tas ;
2015-05-23 00:26:17 -03:00
float k_ff = gains . FF / eas2tas ;
2013-05-31 04:21:20 -03:00
float delta_time = ( float ) dt * 0.001f ;
2013-04-23 16:22:17 -03:00
// Get body rate vector (radians/sec)
2013-08-14 01:56:18 -03:00
float omega_x = _ahrs . get_gyro ( ) . x ;
2013-04-23 16:22:17 -03:00
// Calculate the roll rate error (deg/sec) and apply gain scaler
2014-04-12 01:11:33 -03:00
float achieved_rate = ToDeg ( omega_x ) ;
2020-05-10 04:11:11 -03:00
_pid_info . error = desired_rate - achieved_rate ;
float rate_error = _pid_info . error * scaler ;
_pid_info . target = desired_rate ;
_pid_info . actual = achieved_rate ;
2012-08-21 23:08:14 -03:00
2013-04-23 08:02:18 -03:00
// Get an airspeed estimate - default to zero if none available
float aspeed ;
2020-01-06 20:47:35 -04:00
if ( ! _ahrs . airspeed_estimate ( aspeed ) ) {
2013-05-31 04:21:20 -03:00
aspeed = 0.0f ;
}
2013-04-23 08:02:18 -03:00
2013-10-21 03:58:46 -03:00
// Multiply roll rate error by _ki_rate, apply scaler and integrate
// Scaler is applied before integrator so that integrator state relates directly to aileron deflection
// This means aileron trim offset doesn't change as the value of scaler changes with airspeed
2013-04-23 08:02:18 -03:00
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
2013-08-02 08:54:48 -03:00
if ( ! disable_integrator & & ki_rate > 0 ) {
2013-04-23 08:02:18 -03:00
//only integrate if gain and time step are positive and airspeed above min value.
2016-08-07 21:48:25 -03:00
if ( dt > 0 & & aspeed > float ( aparm . airspeed_min ) ) {
2013-10-21 03:58:46 -03:00
float integrator_delta = rate_error * ki_rate * delta_time * scaler ;
2013-04-23 08:02:18 -03:00
// prevent the integrator from increasing if surface defln demand is above the upper limit
2013-05-31 04:21:20 -03:00
if ( _last_out < - 45 ) {
2015-11-27 13:11:58 -04:00
integrator_delta = MAX ( integrator_delta , 0 ) ;
2013-05-31 04:21:20 -03:00
} else if ( _last_out > 45 ) {
// prevent the integrator from decreasing if surface defln demand is below the lower limit
2015-11-27 13:11:58 -04:00
integrator_delta = MIN ( integrator_delta , 0 ) ;
2013-05-31 04:21:20 -03:00
}
2015-05-22 18:39:38 -03:00
_pid_info . I + = integrator_delta ;
2012-08-21 23:08:14 -03:00
}
} else {
2015-05-22 18:39:38 -03:00
_pid_info . I = 0 ;
2012-08-21 23:08:14 -03:00
}
2013-04-23 08:02:18 -03:00
2013-06-11 05:35:31 -03:00
// Scale the integration limit
2014-04-12 01:11:33 -03:00
float intLimScaled = gains . imax * 0.01f ;
2013-06-11 05:35:31 -03:00
// Constrain the integrator state
2015-05-22 18:39:38 -03:00
_pid_info . I = constrain_float ( _pid_info . I , - intLimScaled , intLimScaled ) ;
2013-06-11 05:35:31 -03:00
2013-04-23 08:02:18 -03:00
// Calculate the demanded control surface deflection
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
// path, but want a 1/speed^2 scaler applied to the rate error path.
2020-09-18 21:29:41 -03:00
// This is because acceleration scales with speed^2, but rate scales with speed.
const float last_pid_info_D = _pid_info . D ;
2015-05-22 18:39:38 -03:00
_pid_info . D = rate_error * gains . D * scaler ;
2015-05-23 00:26:17 -03:00
_pid_info . P = desired_rate * kp_ff * scaler ;
_pid_info . FF = desired_rate * k_ff * scaler ;
2015-05-22 18:39:38 -03:00
2020-05-10 04:11:11 -03:00
if ( dt > 0 & & _slew_rate_max > 0 ) {
// Calculate the slew rate amplitude produced by the unmodified D term
// calculate a low pass filtered slew rate
2020-09-18 21:29:41 -03:00
float Dterm_slew_rate = _slew_rate_filter . apply ( ( fabsf ( _pid_info . D - last_pid_info_D ) / delta_time ) , delta_time ) ;
2020-05-10 04:11:11 -03:00
// rectify and apply a decaying envelope filter
float alpha = 1.0f - constrain_float ( delta_time / _slew_rate_tau , 0.0f , 1.0f ) ;
_slew_rate_amplitude = fmaxf ( fabsf ( Dterm_slew_rate ) , alpha * _slew_rate_amplitude ) ;
_slew_rate_amplitude = fminf ( _slew_rate_amplitude , 10.0f * _slew_rate_max ) ;
// Calculate and apply the D gain adjustment
2020-09-18 21:29:41 -03:00
_pid_info . Dmod = _slew_rate_max / fmaxf ( _slew_rate_amplitude , _slew_rate_max ) ;
_pid_info . D * = _pid_info . Dmod ;
2020-05-10 04:11:11 -03:00
}
_last_out = _pid_info . D + _pid_info . FF + _pid_info . P ;
2014-04-12 01:11:33 -03:00
2016-08-07 21:48:25 -03:00
if ( autotune . running & & aspeed > aparm . airspeed_min ) {
2014-04-12 01:11:33 -03:00
// let autotune have a go at the values
// Note that we don't pass the integrator component so we get
// a better idea of how much the base PD controller
// contributed
autotune . update ( desired_rate , achieved_rate , _last_out ) ;
}
2015-05-22 18:39:38 -03:00
_last_out + = _pid_info . I ;
2013-04-23 08:02:18 -03:00
// Convert to centi-degrees and constrain
2013-05-05 01:34:33 -03:00
return constrain_float ( _last_out * 100 , - 4500 , 4500 ) ;
2012-08-21 23:08:14 -03:00
}
2020-09-18 21:29:41 -03:00
/*
AC_PID based rate controller
*/
int32_t AP_RollController : : _get_rate_out_ac_pid ( float desired_rate , float scaler , bool disable_integrator )
{
convert_pid ( ) ;
const float dt = AP : : scheduler ( ) . get_loop_period_s ( ) ;
const float eas2tas = _ahrs . get_EAS2TAS ( ) ;
bool limit_I = fabsf ( last_ac_out ) > = 45 ;
float rate_x = _ahrs . get_gyro ( ) . x ;
float aspeed ;
float old_I = rate_pid . get_i ( ) ;
rate_pid . set_dt ( dt ) ;
if ( ! _ahrs . airspeed_estimate ( aspeed ) ) {
aspeed = 0 ;
}
bool underspeed = aspeed < = float ( aparm . airspeed_min ) ;
if ( underspeed ) {
limit_I = true ;
}
// the P and I elements are scaled by sq(scaler). To use an
// unmodified AC_PID object we scale the inputs and calculate FF separately
//
// note that we run AC_PID in radians so that the normal scaling
// range for IMAX in AC_PID applies (usually an IMAX value less than 1.0)
rate_pid . update_all ( radians ( desired_rate ) * scaler * scaler , rate_x * scaler * scaler , limit_I ) ;
if ( underspeed ) {
// when underspeed we lock the integrator
rate_pid . set_integrator ( old_I ) ;
}
// FF should be scaled by scaler/eas2tas, but since we have scaled
// the AC_PID target above by scaler*scaler we need to instead
// divide by scaler*eas2tas to get the right scaling
const float ff = degrees ( rate_pid . get_ff ( ) / ( scaler * eas2tas ) ) ;
if ( disable_integrator ) {
rate_pid . reset_I ( ) ;
}
// convert AC_PID info object to same scale as old controller
_pid_info_ac_pid = rate_pid . get_pid_info ( ) ;
auto & pinfo = _pid_info_ac_pid ;
const float deg_scale = degrees ( 1 ) ;
pinfo . FF = ff ;
pinfo . P * = deg_scale ;
pinfo . I * = deg_scale ;
pinfo . D * = deg_scale ;
// fix the logged target and actual values to not have the scalers applied
pinfo . target = desired_rate ;
pinfo . actual = degrees ( rate_x ) ;
// sum components
float out = pinfo . FF + pinfo . P + pinfo . I + pinfo . D ;
// remember the last output to trigger the I limit
last_ac_out = out ;
// output is scaled to notional centidegrees of deflection
return constrain_int32 ( out * 100 , - 4500 , 4500 ) ;
}
/*
rate controller selector
*/
int32_t AP_RollController : : _get_rate_out ( float desired_rate , float scaler , bool disable_integrator )
{
int32_t ret_ac_pid = _get_rate_out_ac_pid ( desired_rate , scaler , disable_integrator ) ;
int32_t ret_old = _get_rate_out_old ( desired_rate , scaler , disable_integrator ) ;
const auto & pinfo_ac = _pid_info_ac_pid ;
const auto & pinfo_old = _pid_info ;
AP : : logger ( ) . Write ( " PIXR " , " TimeUS,AC,Old,ACSum,OldSum " , " Qiiff " ,
AP_HAL : : micros64 ( ) ,
ret_ac_pid ,
ret_old ,
pinfo_ac . FF + pinfo_ac . P + pinfo_ac . I + pinfo_ac . D ,
pinfo_old . FF + pinfo_old . P + pinfo_old . I + pinfo_old . D ) ;
return use_ac_pid ? ret_ac_pid : ret_old ;
}
2013-07-10 10:25:06 -03:00
/*
Function returns an equivalent elevator deflection in centi - degrees in the range from - 4500 to 4500
A positive demand is up
Inputs are :
1 ) desired roll rate in degrees / sec
2 ) control gain scaler = scaling_speed / aspeed
*/
int32_t AP_RollController : : get_rate_out ( float desired_rate , float scaler )
{
2013-10-04 09:16:24 -03:00
return _get_rate_out ( desired_rate , scaler , false ) ;
2013-07-10 10:25:06 -03:00
}
/*
2018-05-29 05:01:44 -03:00
Function returns an equivalent aileron deflection in centi - degrees in the range from - 4500 to 4500
2013-07-10 10:25:06 -03:00
A positive demand is up
Inputs are :
1 ) demanded bank angle in centi - degrees
2 ) control gain scaler = scaling_speed / aspeed
3 ) boolean which is true when stabilise mode is active
4 ) minimum FBW airspeed ( metres / sec )
*/
2013-08-02 08:54:48 -03:00
int32_t AP_RollController : : get_servo_out ( int32_t angle_err , float scaler , bool disable_integrator )
2013-07-10 10:25:06 -03:00
{
2014-07-08 07:26:20 -03:00
if ( gains . tau < 0.1f ) {
2014-04-12 01:11:33 -03:00
gains . tau . set ( 0.1f ) ;
2013-07-10 10:25:06 -03:00
}
// Calculate the desired roll rate (deg/sec) from the angle error
2014-04-12 01:11:33 -03:00
float desired_rate = angle_err * 0.01f / gains . tau ;
2013-07-10 10:25:06 -03:00
2019-05-01 08:54:23 -03:00
// Limit the demanded roll rate
if ( gains . rmax & & desired_rate < - gains . rmax ) {
desired_rate = - gains . rmax ;
} else if ( gains . rmax & & desired_rate > gains . rmax ) {
desired_rate = gains . rmax ;
}
2013-08-02 08:54:48 -03:00
return _get_rate_out ( desired_rate , scaler , disable_integrator ) ;
2013-07-10 10:25:06 -03:00
}
2012-08-21 23:08:14 -03:00
void AP_RollController : : reset_I ( )
{
2015-05-22 18:39:38 -03:00
_pid_info . I = 0 ;
2020-09-18 21:29:41 -03:00
rate_pid . reset_I ( ) ;
}
/*
convert from old to new PIDs
this is a temporary conversion function during development
*/
void AP_RollController : : convert_pid ( )
{
if ( done_init & & is_positive ( rate_pid . ff ( ) ) ) {
return ;
}
done_init = true ;
AP_Float & ff = rate_pid . ff ( ) ;
if ( is_positive ( ff ) & & ff . configured_in_storage ( ) ) {
return ;
}
const float kp_ff = MAX ( ( gains . P - gains . I * gains . tau ) * gains . tau - gains . D , 0 ) ;
rate_pid . ff ( ) . set_and_save ( gains . FF + kp_ff ) ;
rate_pid . kI ( ) . set_and_save_ifchanged ( gains . I * gains . tau ) ;
rate_pid . kP ( ) . set_and_save_ifchanged ( gains . D ) ;
rate_pid . kD ( ) . set_and_save_ifchanged ( 0 ) ;
rate_pid . kIMAX ( ) . set_and_save_ifchanged ( gains . imax / 4500.0 ) ;
2012-08-21 23:08:14 -03:00
}