2013-05-29 20:53:02 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
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 .
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 .
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 to implement a three loop autopilot
// topology
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_YawController.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_YawController : : var_info [ ] = {
2013-05-05 03:15:26 -03:00
2013-05-30 09:57:49 -03:00
// @Param: SLIP
2013-05-05 03:15:26 -03:00
// @DisplayName: Sideslip control gain
2013-05-30 09:57:49 -03:00
// @Description: This is the gain from measured lateral acceleration to demanded yaw rate. It should be set to zero unless active control of sideslip is desired. This will only work effectively if there is enough fuselage side area to generate a measureable lateral acceleration when the model sideslips. Flying wings and most gliders cannot use this term. This term should only be adjusted after the basic yaw damper gain YAW2SRV_DAMP is tuned and the YAW2SRV_INT integrator gain has been set. Set this gain to zero if only yaw damping is required.
2013-05-05 03:15:26 -03:00
// @Range: 0 4
// @Increment: 0.25
2013-05-30 09:57:49 -03:00
AP_GROUPINFO ( " SLIP " , 0 , AP_YawController , _K_A , 0 ) ,
2013-05-05 03:15:26 -03:00
2013-05-30 09:57:49 -03:00
// @Param: INT
2015-06-24 05:23:10 -03:00
// @DisplayName: Sideslip control integrator
2013-05-05 03:15:26 -03:00
// @Description: This is the integral gain from lateral acceleration error. This gain should only be non-zero if active control over sideslip is desired. If active control over sideslip is required then this can be set to 1.0 as a first try.
// @Range: 0 2
// @Increment: 0.25
2013-05-30 09:57:49 -03:00
AP_GROUPINFO ( " INT " , 1 , AP_YawController , _K_I , 0 ) ,
2013-05-05 03:15:26 -03:00
2013-05-30 09:57:49 -03:00
// @Param: DAMP
2013-05-05 03:15:26 -03:00
// @DisplayName: Yaw damping
2013-07-15 20:42:54 -03:00
// @Description: This is the gain from yaw rate to rudder. It acts as a damper on yaw motion. If a basic yaw damper is required, this gain term can be incremented, whilst leaving the YAW2SRV_SLIP and YAW2SRV_INT gains at zero. Note that unlike with a standard PID controller, if this damping term is zero then the integrator will also be disabled.
2013-05-05 03:15:26 -03:00
// @Range: 0 2
// @Increment: 0.25
2013-05-30 09:57:49 -03:00
AP_GROUPINFO ( " DAMP " , 2 , AP_YawController , _K_D , 0 ) ,
2013-05-05 03:15:26 -03:00
2013-05-30 09:57:49 -03:00
// @Param: RLL
2013-05-05 03:15:26 -03:00
// @DisplayName: Yaw coordination gain
// @Description: This is the gain term that is applied to the yaw rate offset calculated as required to keep the yaw rate consistent with the turn rate for a coordinated turn. The default value is 1 which will work for all models. Advanced users can use it to correct for any tendency to yaw away from or into the turn once the turn is established. Increase to make the model yaw more initially and decrease to make the model yaw less initially. If values greater than 1.1 or less than 0.9 are required then it normally indicates a problem with the airspeed calibration.
// @Range: 0.8 1.2
// @Increment: 0.05
2013-05-30 09:57:49 -03:00
AP_GROUPINFO ( " RLL " , 3 , AP_YawController , _K_FF , 1 ) ,
2013-05-05 03:15:26 -03:00
2013-07-15 20:42:54 -03:00
/*
Note : index 4 should not be used - it was used for an incorrect
AP_Int8 version of the IMAX in the 2.74 release
*/
2013-06-11 05:35:31 -03:00
// @Param: IMAX
// @DisplayName: Integrator limit
2013-06-22 08:08:37 -03:00
// @Description: This limits the number of centi-degrees of rudder over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 degrees, so the default value represents a 1/3rd of the total control throw which is adequate for most aircraft unless they are severely out of trim or have very limited rudder control effectiveness.
// @Range: 0 4500
2013-06-11 05:35:31 -03:00
// @Increment: 1
// @User: Advanced
2013-07-15 20:42:54 -03:00
AP_GROUPINFO ( " IMAX " , 5 , AP_YawController , _imax , 1500 ) ,
2013-06-11 05:35:31 -03:00
2012-08-21 23:08:14 -03:00
AP_GROUPEND
} ;
2013-08-02 08:54:48 -03:00
int32_t AP_YawController : : get_servo_out ( 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 ;
2016-08-07 21:48:25 -03:00
int16_t aspd_min = aparm . airspeed_min ;
if ( aspd_min < 1 ) {
aspd_min = 1 ;
}
2012-08-21 23:08:14 -03:00
2013-01-10 14:42:24 -04:00
float delta_time = ( float ) dt / 1000.0f ;
2012-08-21 23:08:14 -03:00
2013-04-23 08:02:18 -03:00
// Calculate yaw rate required to keep up with a constant height coordinated turn
float aspeed ;
float rate_offset ;
2013-08-14 01:56:18 -03:00
float bank_angle = _ahrs . roll ;
2013-04-23 08:02:18 -03:00
// limit bank angle between +- 80 deg if right way up
if ( fabsf ( bank_angle ) < 1.5707964f ) {
2013-05-05 01:34:33 -03:00
bank_angle = constrain_float ( bank_angle , - 1.3962634f , 1.3962634f ) ;
2013-04-23 08:02:18 -03:00
}
2013-08-14 01:56:18 -03:00
if ( ! _ahrs . airspeed_estimate ( & aspeed ) ) {
2013-04-23 08:02:18 -03:00
// If no airspeed available use average of min and max
2016-08-07 21:48:25 -03:00
aspeed = 0.5f * ( float ( aspd_min ) + float ( aparm . airspeed_max ) ) ;
2012-08-21 23:08:14 -03:00
}
2016-08-07 21:48:25 -03:00
rate_offset = ( GRAVITY_MSS / MAX ( aspeed , float ( aspd_min ) ) ) * tanf ( bank_angle ) * cosf ( bank_angle ) * _K_FF ;
2012-08-21 23:08:14 -03:00
2013-04-23 16:22:17 -03:00
// Get body rate vector (radians/sec)
2013-08-14 01:56:18 -03:00
float omega_z = _ahrs . get_gyro ( ) . z ;
2013-04-23 08:02:18 -03:00
// Get the accln vector (m/s^2)
2013-11-03 23:35:44 -04:00
float accel_y = _ahrs . get_ins ( ) . get_accel ( ) . y ;
2013-04-23 08:02:18 -03:00
2013-04-23 16:22:17 -03:00
// Subtract the steady turn component of rate from the measured rate
// to calculate the rate relative to the turn requirement in degrees/sec
2013-05-05 01:34:33 -03:00
float rate_hp_in = ToDeg ( omega_z - rate_offset ) ;
2013-04-23 16:22:17 -03:00
// Apply a high-pass filter to the rate to washout any steady state error
// due to bias errors in rate_offset
// Use a cut-off frequency of omega = 0.2 rad/sec
// Could make this adjustable by replacing 0.9960080 with (1 - omega * dt)
float rate_hp_out = 0.9960080f * _last_rate_hp_out + rate_hp_in - _last_rate_hp_in ;
_last_rate_hp_out = rate_hp_out ;
_last_rate_hp_in = rate_hp_in ;
2013-04-23 08:02:18 -03:00
//Calculate input to integrator
float integ_in = - _K_I * ( _K_A * accel_y + rate_hp_out ) ;
2012-08-21 23:08:14 -03:00
2013-04-23 08:02:18 -03:00
// Apply integrator, but clamp input to prevent control saturation and freeze integrator below min FBW speed
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
// Don't integrate if _K_D is zero as integrator will keep winding up
2013-08-02 08:54:48 -03:00
if ( ! disable_integrator & & _K_D > 0 ) {
2013-04-23 08:02:18 -03:00
//only integrate if airspeed above min value
2016-08-07 21:48:25 -03:00
if ( aspeed > float ( aspd_min ) )
2013-04-23 08:02:18 -03:00
{
// prevent the integrator from increasing if surface defln demand is above the upper limit
2013-06-01 04:00:10 -03:00
if ( _last_out < - 45 ) {
2015-11-27 13:11:58 -04:00
_integrator + = MAX ( integ_in * delta_time , 0 ) ;
2013-06-01 04:00:10 -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 + = MIN ( integ_in * delta_time , 0 ) ;
2013-06-01 04:00:10 -03:00
} else {
_integrator + = integ_in * delta_time ;
}
2012-08-21 23:08:14 -03:00
}
} else {
_integrator = 0 ;
}
2013-07-15 20:42:54 -03:00
if ( _K_D < 0.0001f ) {
// yaw damping is disabled, and the integrator is scaled by damping, so return 0
return 0 ;
}
2012-08-21 23:08:14 -03:00
2013-06-11 05:35:31 -03:00
// Scale the integration limit
2013-06-22 08:08:37 -03:00
float intLimScaled = _imax * 0.01f / ( _K_D * scaler * scaler ) ;
2013-06-11 05:35:31 -03:00
// Constrain the integrator state
_integrator = constrain_float ( _integrator , - intLimScaled , intLimScaled ) ;
2013-04-23 08:02:18 -03:00
// Protect against increases to _K_D during in-flight tuning from creating large control transients
// due to stored integrator values
if ( _K_D > _K_D_last & & _K_D > 0 ) {
_integrator = _K_D_last / _K_D * _integrator ;
}
_K_D_last = _K_D ;
// Calculate demanded rudder deflection, +Ve deflection yaws nose right
// Save to last value before application of limiter so that integrator limiting
// can detect exceedance next frame
// Scale using inverse dynamic pressure (1/V^2)
2015-06-22 00:28:08 -03:00
_pid_info . I = _K_D * _integrator * scaler * scaler ;
_pid_info . D = _K_D * ( - rate_hp_out ) * scaler * scaler ;
_last_out = _pid_info . I + _pid_info . D ;
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
}
void AP_YawController : : reset_I ( )
{
_integrator = 0 ;
}