APM:Libraries
AP_RollController.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
18 //
19 
20 #include <AP_HAL/AP_HAL.h>
21 #include "AP_RollController.h"
22 
23 extern const AP_HAL::HAL& hal;
24 
26  // @Param: TCONST
27  // @DisplayName: Roll Time Constant
28  // @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve.
29  // @Range: 0.4 1.0
30  // @Units: s
31  // @Increment: 0.1
32  // @User: Advanced
33  AP_GROUPINFO("TCONST", 0, AP_RollController, gains.tau, 0.5f),
34 
35  // @Param: P
36  // @DisplayName: Proportional Gain
37  // @Description: This is the gain from bank angle error to aileron.
38  // @Range: 0.1 4.0
39  // @Increment: 0.1
40  // @User: User
41  AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.6f),
42 
43  // @Param: D
44  // @DisplayName: Damping Gain
45  // @Description: This is the gain from roll rate to aileron. This adjusts the damping of the roll control loop. It has the same effect as RLL2SRV_D in the old PID controller but without the spikes in servo demands. This gain helps to reduce rolling in turbulence. It should be increased in 0.01 increments as too high a value can lead to a high frequency roll oscillation that could overstress the airframe.
46  // @Range: 0 0.1
47  // @Increment: 0.01
48  // @User: User
49  AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.02f),
50 
51  // @Param: I
52  // @DisplayName: Integrator Gain
53  // @Description: This is the gain from the integral of bank angle to aileron. It has the same effect as RLL2SRV_I in the old PID controller. Increasing this gain causes the controller to trim out steady offsets due to an out of trim aircraft.
54  // @Range: 0 1.0
55  // @Increment: 0.05
56  // @User: User
57  AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.1f),
58 
59  // @Param: RMAX
60  // @DisplayName: Maximum Roll Rate
61  // @Description: This sets the maximum roll rate that the controller will demand (degrees/sec). Setting it to zero disables the limit. If this value is set too low, then the roll can't keep up with the navigation demands and the plane will start weaving. If it is set too high (or disabled by setting to zero) then ailerons will get large inputs at the start of turns. A limit of 60 degrees/sec is a good default.
62  // @Range: 0 180
63  // @Units: deg/s
64  // @Increment: 1
65  // @User: Advanced
66  AP_GROUPINFO("RMAX", 4, AP_RollController, gains.rmax, 0),
67 
68  // @Param: IMAX
69  // @DisplayName: Integrator limit
70  // @Description: This limits the number of degrees of aileron in centi-degrees over which the integrator will operate. At the default setting of 3000 centi-degrees, the integrator will be limited to +- 30 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 2/3rd of the total control throw which is adequate unless the aircraft is severely out of trim.
71  // @Range: 0 4500
72  // @Increment: 1
73  // @User: Advanced
74  AP_GROUPINFO("IMAX", 5, AP_RollController, gains.imax, 3000),
75 
76  // @Param: FF
77  // @DisplayName: Feed forward Gain
78  // @Description: This is the gain from demanded rate to aileron output.
79  // @Range: 0.1 4.0
80  // @Increment: 0.1
81  // @User: User
82  AP_GROUPINFO("FF", 6, AP_RollController, gains.FF, 0.0f),
83 
85 };
86 
87 
88 /*
89  internal rate controller, called by attitude and rate controller
90  public functions
91 */
92 int32_t AP_RollController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator)
93 {
94  uint32_t tnow = AP_HAL::millis();
95  uint32_t dt = tnow - _last_t;
96  if (_last_t == 0 || dt > 1000) {
97  dt = 0;
98  }
99  _last_t = tnow;
100 
101  // Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
102  // No conversion is required for K_D
103  float ki_rate = gains.I * gains.tau;
104  float eas2tas = _ahrs.get_EAS2TAS();
105  float kp_ff = MAX((gains.P - gains.I * gains.tau) * gains.tau - gains.D , 0) / eas2tas;
106  float k_ff = gains.FF / eas2tas;
107  float delta_time = (float)dt * 0.001f;
108 
109  // Limit the demanded roll rate
110  if (gains.rmax && desired_rate < -gains.rmax) {
111  desired_rate = - gains.rmax;
112  } else if (gains.rmax && desired_rate > gains.rmax) {
113  desired_rate = gains.rmax;
114  }
115 
116  // Get body rate vector (radians/sec)
117  float omega_x = _ahrs.get_gyro().x;
118 
119  // Calculate the roll rate error (deg/sec) and apply gain scaler
120  float achieved_rate = ToDeg(omega_x);
121  float rate_error = (desired_rate - achieved_rate) * scaler;
122 
123  // Get an airspeed estimate - default to zero if none available
124  float aspeed;
125  if (!_ahrs.airspeed_estimate(&aspeed)) {
126  aspeed = 0.0f;
127  }
128 
129  // Multiply roll rate error by _ki_rate, apply scaler and integrate
130  // Scaler is applied before integrator so that integrator state relates directly to aileron deflection
131  // This means aileron trim offset doesn't change as the value of scaler changes with airspeed
132  // Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
133  if (!disable_integrator && ki_rate > 0) {
134  //only integrate if gain and time step are positive and airspeed above min value.
135  if (dt > 0 && aspeed > float(aparm.airspeed_min)) {
136  float integrator_delta = rate_error * ki_rate * delta_time * scaler;
137  // prevent the integrator from increasing if surface defln demand is above the upper limit
138  if (_last_out < -45) {
139  integrator_delta = MAX(integrator_delta , 0);
140  } else if (_last_out > 45) {
141  // prevent the integrator from decreasing if surface defln demand is below the lower limit
142  integrator_delta = MIN(integrator_delta, 0);
143  }
144  _pid_info.I += integrator_delta;
145  }
146  } else {
147  _pid_info.I = 0;
148  }
149 
150  // Scale the integration limit
151  float intLimScaled = gains.imax * 0.01f;
152 
153  // Constrain the integrator state
154  _pid_info.I = constrain_float(_pid_info.I, -intLimScaled, intLimScaled);
155 
156  // Calculate the demanded control surface deflection
157  // Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
158  // path, but want a 1/speed^2 scaler applied to the rate error path.
159  // This is because acceleration scales with speed^2, but rate scales with speed.
160  _pid_info.D = rate_error * gains.D * scaler;
161  _pid_info.P = desired_rate * kp_ff * scaler;
162  _pid_info.FF = desired_rate * k_ff * scaler;
163  _pid_info.desired = desired_rate;
164 
166 
167  if (autotune.running && aspeed > aparm.airspeed_min) {
168  // let autotune have a go at the values
169  // Note that we don't pass the integrator component so we get
170  // a better idea of how much the base PD controller
171  // contributed
172  autotune.update(desired_rate, achieved_rate, _last_out);
173  }
174 
175  _last_out += _pid_info.I;
176 
177  // Convert to centi-degrees and constrain
178  return constrain_float(_last_out * 100, -4500, 4500);
179 }
180 
181 
182 /*
183  Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
184  A positive demand is up
185  Inputs are:
186  1) desired roll rate in degrees/sec
187  2) control gain scaler = scaling_speed / aspeed
188 */
189 int32_t AP_RollController::get_rate_out(float desired_rate, float scaler)
190 {
191  return _get_rate_out(desired_rate, scaler, false);
192 }
193 
194 /*
195  Function returns an equivalent aileron deflection in centi-degrees in the range from -4500 to 4500
196  A positive demand is up
197  Inputs are:
198  1) demanded bank angle in centi-degrees
199  2) control gain scaler = scaling_speed / aspeed
200  3) boolean which is true when stabilise mode is active
201  4) minimum FBW airspeed (metres/sec)
202 */
203 int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
204 {
205  if (gains.tau < 0.1f) {
206  gains.tau.set(0.1f);
207  }
208 
209  // Calculate the desired roll rate (deg/sec) from the angle error
210  float desired_rate = angle_err * 0.01f / gains.tau;
211 
212  return _get_rate_out(desired_rate, scaler, disable_integrator);
213 }
214 
216 {
217  _pid_info.I = 0;
218 }
219 
virtual const Vector3f & get_gyro(void) const =0
int32_t get_rate_out(float desired_rate, float scaler)
void update(float desired_rate, float achieved_rate, float servo_out)
#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
AP_AutoTune::ATGains gains
bool running
Definition: AP_AutoTune.h:51
#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
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator)
#define f(i)
uint32_t millis()
Definition: system.cpp:157
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
const AP_Vehicle::FixedWing & aparm
static const struct AP_Param::GroupInfo var_info[]
DataFlash_Class::PID_Info _pid_info
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
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 AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67