APM:Libraries
AP_YawController.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 // Code by Jon Challinger
17 // Modified by Paul Riseborough to implement a three loop autopilot
18 // topology
19 //
20 #include <AP_HAL/AP_HAL.h>
21 #include "AP_YawController.h"
22 
23 extern const AP_HAL::HAL& hal;
24 
26 
27  // @Param: SLIP
28  // @DisplayName: Sideslip control gain
29  // @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.
30  // @Range: 0 4
31  // @Increment: 0.25
32  // @User: Advanced
33  AP_GROUPINFO("SLIP", 0, AP_YawController, _K_A, 0),
34 
35  // @Param: INT
36  // @DisplayName: Sideslip control integrator
37  // @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.
38  // @Range: 0 2
39  // @Increment: 0.25
40  // @User: Advanced
41  AP_GROUPINFO("INT", 1, AP_YawController, _K_I, 0),
42 
43  // @Param: DAMP
44  // @DisplayName: Yaw damping
45  // @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.
46  // @Range: 0 2
47  // @Increment: 0.25
48  // @User: Advanced
49  AP_GROUPINFO("DAMP", 2, AP_YawController, _K_D, 0),
50 
51  // @Param: RLL
52  // @DisplayName: Yaw coordination gain
53  // @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.
54  // @Range: 0.8 1.2
55  // @Increment: 0.05
56  // @User: Advanced
57  AP_GROUPINFO("RLL", 3, AP_YawController, _K_FF, 1),
58 
59  /*
60  Note: index 4 should not be used - it was used for an incorrect
61  AP_Int8 version of the IMAX in the 2.74 release
62  */
63 
64 
65  // @Param: IMAX
66  // @DisplayName: Integrator limit
67  // @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.
68  // @Range: 0 4500
69  // @Increment: 1
70  // @User: Advanced
71  AP_GROUPINFO("IMAX", 5, AP_YawController, _imax, 1500),
72 
74 };
75 
76 int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
77 {
78  uint32_t tnow = AP_HAL::millis();
79  uint32_t dt = tnow - _last_t;
80  if (_last_t == 0 || dt > 1000) {
81  dt = 0;
82  }
83  _last_t = tnow;
84 
85 
86  int16_t aspd_min = aparm.airspeed_min;
87  if (aspd_min < 1) {
88  aspd_min = 1;
89  }
90 
91  float delta_time = (float) dt / 1000.0f;
92 
93  // Calculate yaw rate required to keep up with a constant height coordinated turn
94  float aspeed;
95  float rate_offset;
96  float bank_angle = _ahrs.roll;
97  // limit bank angle between +- 80 deg if right way up
98  if (fabsf(bank_angle) < 1.5707964f) {
99  bank_angle = constrain_float(bank_angle,-1.3962634f,1.3962634f);
100  }
101  if (!_ahrs.airspeed_estimate(&aspeed)) {
102  // If no airspeed available use average of min and max
103  aspeed = 0.5f*(float(aspd_min) + float(aparm.airspeed_max));
104  }
105  rate_offset = (GRAVITY_MSS / MAX(aspeed , float(aspd_min))) * sinf(bank_angle) * _K_FF;
106 
107  // Get body rate vector (radians/sec)
108  float omega_z = _ahrs.get_gyro().z;
109 
110  // Get the accln vector (m/s^2)
111  float accel_y = AP::ins().get_accel().y;
112 
113  // Subtract the steady turn component of rate from the measured rate
114  // to calculate the rate relative to the turn requirement in degrees/sec
115  float rate_hp_in = ToDeg(omega_z - rate_offset);
116 
117  // Apply a high-pass filter to the rate to washout any steady state error
118  // due to bias errors in rate_offset
119  // Use a cut-off frequency of omega = 0.2 rad/sec
120  // Could make this adjustable by replacing 0.9960080 with (1 - omega * dt)
121  float rate_hp_out = 0.9960080f * _last_rate_hp_out + rate_hp_in - _last_rate_hp_in;
122  _last_rate_hp_out = rate_hp_out;
123  _last_rate_hp_in = rate_hp_in;
124 
125  //Calculate input to integrator
126  float integ_in = - _K_I * (_K_A * accel_y + rate_hp_out);
127 
128  // Apply integrator, but clamp input to prevent control saturation and freeze integrator below min FBW speed
129  // Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
130  // Don't integrate if _K_D is zero as integrator will keep winding up
131  if (!disable_integrator && _K_D > 0) {
132  //only integrate if airspeed above min value
133  if (aspeed > float(aspd_min))
134  {
135  // prevent the integrator from increasing if surface defln demand is above the upper limit
136  if (_last_out < -45) {
137  _integrator += MAX(integ_in * delta_time , 0);
138  } else if (_last_out > 45) {
139  // prevent the integrator from decreasing if surface defln demand is below the lower limit
140  _integrator += MIN(integ_in * delta_time , 0);
141  } else {
142  _integrator += integ_in * delta_time;
143  }
144  }
145  } else {
146  _integrator = 0;
147  }
148 
149  if (_K_D < 0.0001f) {
150  // yaw damping is disabled, and the integrator is scaled by damping, so return 0
151  return 0;
152  }
153 
154  // Scale the integration limit
155  float intLimScaled = _imax * 0.01f / (_K_D * scaler * scaler);
156 
157  // Constrain the integrator state
158  _integrator = constrain_float(_integrator, -intLimScaled, intLimScaled);
159 
160  // Protect against increases to _K_D during in-flight tuning from creating large control transients
161  // due to stored integrator values
162  if (_K_D > _K_D_last && _K_D > 0) {
164  }
165  _K_D_last = _K_D;
166 
167  // Calculate demanded rudder deflection, +Ve deflection yaws nose right
168  // Save to last value before application of limiter so that integrator limiting
169  // can detect exceedance next frame
170  // Scale using inverse dynamic pressure (1/V^2)
171  _pid_info.I = _K_D * _integrator * scaler * scaler;
172  _pid_info.D = _K_D * (-rate_hp_out) * scaler * scaler;
174 
175  // Convert to centi-degrees and constrain
176  return constrain_float(_last_out * 100, -4500, 4500);
177 }
178 
180 {
181  _integrator = 0;
182 }
float roll
Definition: AP_AHRS.h:224
virtual const Vector3f & get_gyro(void) const =0
DataFlash_Class::PID_Info _pid_info
static const struct AP_Param::GroupInfo var_info[]
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
virtual bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS.cpp:170
int32_t get_servo_out(float scaler, bool disable_integrator)
#define MIN(a, b)
Definition: usb_conf.h:215
#define ToDeg(x)
Definition: AP_Common.h:54
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
const AP_Vehicle::FixedWing & aparm
const Vector3f & get_accel(uint8_t i) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
T z
Definition: vector3.h:67
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
AP_InertialSensor & ins()
#define AP_GROUPEND
Definition: AP_Param.h:121