APM:Libraries
AP_SteerController.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 Andrew Tridgell
17 // Based upon the roll controller by Paul Riseborough and Jon Challinger
18 //
19 
20 #include <AP_Math/AP_Math.h>
21 #include <AP_HAL/AP_HAL.h>
22 #include "AP_SteerController.h"
23 
24 extern const AP_HAL::HAL& hal;
25 
27  // @Param: TCONST
28  // @DisplayName: Steering Time Constant
29  // @Description: This controls the time constant in seconds from demanded to achieved steering angle. A value of 0.75 is a good default and will work with nearly all rovers. Ground steering in aircraft needs a bit smaller time constant, and a value of 0.5 is recommended for best ground handling in fixed wing aircraft. A value of 0.75 means that the controller will try to correct any deviation between the desired and actual steering angle in 0.75 seconds. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the vehicle can achieve.
30  // @Range: 0.4 1.0
31  // @Units: s
32  // @Increment: 0.1
33  // @User: Advanced
34  AP_GROUPINFO("TCONST", 0, AP_SteerController, _tau, 0.75f),
35 
36  // @Param: P
37  // @DisplayName: Steering turning gain
38  // @Description: The proportional gain for steering. This should be approximately equal to the diameter of the turning circle of the vehicle at low speed and maximum steering angle
39  // @Range: 0.1 10.0
40  // @Increment: 0.1
41  // @User: User
42  AP_GROUPINFO("P", 1, AP_SteerController, _K_P, 1.8f),
43 
44  // @Param: I
45  // @DisplayName: Integrator Gain
46  // @Description: This is the gain from the integral of steering angle. Increasing this gain causes the controller to trim out steady offsets due to an out of trim vehicle.
47  // @Range: 0 1.0
48  // @Increment: 0.05
49  // @User: User
50  AP_GROUPINFO("I", 3, AP_SteerController, _K_I, 0.2f),
51 
52  // @Param: D
53  // @DisplayName: Damping Gain
54  // @Description: This adjusts the damping of the steering control loop. This gain helps to reduce steering jitter with vibration. It should be increased in 0.01 increments as too high a value can lead to a high frequency steering oscillation that could overstress the vehicle.
55  // @Range: 0 0.1
56  // @Increment: 0.01
57  // @User: User
58  AP_GROUPINFO("D", 4, AP_SteerController, _K_D, 0.005f),
59 
60  // @Param: IMAX
61  // @DisplayName: Integrator limit
62  // @Description: This limits the number of degrees of steering in centi-degrees 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 centi-degrees, so the default value represents a 1/3rd of the total control throw which is adequate unless the vehicle is severely out of trim.
63  // @Range: 0 4500
64  // @Increment: 1
65  // @Units: cdeg
66  // @User: Advanced
67  AP_GROUPINFO("IMAX", 5, AP_SteerController, _imax, 1500),
68 
69  // @Param: MINSPD
70  // @DisplayName: Minimum speed
71  // @Description: This is the minimum assumed ground speed in meters/second for steering. Having a minimum speed prevents oscillations when the vehicle first starts moving. The vehicle can still drive slower than this limit, but the steering calculations will be done based on this minimum speed.
72  // @Range: 0 5
73  // @Increment: 0.1
74  // @Units: m/s
75  // @User: User
76  AP_GROUPINFO("MINSPD", 6, AP_SteerController, _minspeed, 1.0f),
77 
78 
79  // @Param: FF
80  // @DisplayName: Steering feed forward
81  // @Description: The feed forward gain for steering this is the ratio of the achieved turn rate to applied steering. A value of 1 means that the vehicle would yaw at a rate of 45 degrees per second with full steering deflection at 1m/s ground speed.
82  // @Range: 0.0 10.0
83  // @Increment: 0.1
84  // @User: User
85  AP_GROUPINFO("FF", 7, AP_SteerController, _K_FF, 0),
86 
87 
88  // @Param: DRTSPD
89  // @DisplayName: Derating speed
90  // @Description: Speed after that the maximum degree of steering will start to derate. Set this speed to a maximum speed that a plane can do controlled turn at maximum angle of steering wheel without rolling to wing. If 0 then no derating is used.
91  // @Range: 0.0 30.0
92  // @Increment: 0.1
93  // @Units: m/s
94  // @User: Advanced
95  AP_GROUPINFO("DRTSPD", 8, AP_SteerController, _deratespeed, 0),
96 
97  // @Param: DRTFCT
98  // @DisplayName: Derating factor
99  // @Description: Degrees of steering wheel to derate at each additional m/s of speed above "Derating speed". Should be set so that at higher speeds the plane does not roll to the wing in turns.
100  // @Range: 0.0 50.0
101  // @Increment: 0.1
102  // @Units: deg/m/s
103  // @User: Advanced
104  AP_GROUPINFO("DRTFCT", 9, AP_SteerController, _deratefactor, 10),
105 
106  // @Param: DRTMIN
107  // @DisplayName: Minimum angle of wheel
108  // @Description: The angle that limits smallest angle of steering wheel at maximum speed. Even if it should derate below, it will stop derating at this angle.
109  // @Range: 0.0 4500.0
110  // @Increment: 0.1
111  // @Units: cdeg
112  // @User: Advanced
113  AP_GROUPINFO("DRTMIN", 10, AP_SteerController, _mindegree, 4500),
114 
116 };
117 
118 
119 /*
120  steering rate controller. Returns servo out -4500 to 4500 given
121  desired yaw rate in degrees/sec. Positive yaw rate means clockwise yaw.
122 */
123 int32_t AP_SteerController::get_steering_out_rate(float desired_rate)
124 {
125  uint32_t tnow = AP_HAL::millis();
126  uint32_t dt = tnow - _last_t;
127  if (_last_t == 0 || dt > 1000) {
128  dt = 0;
129  }
130  _last_t = tnow;
131 
132  float speed = _ahrs.groundspeed();
133  if (speed < _minspeed) {
134  // assume a minimum speed. This stops oscillations when first starting to move
135  speed = _minspeed;
136  }
137 
138  // this is a linear approximation of the inverse steering
139  // equation for a ground vehicle. It returns steering as an angle from -45 to 45
140  float scaler = 1.0f / speed;
141 
142  _pid_info.desired = desired_rate;
143 
144  // Calculate the steering rate error (deg/sec) and apply gain scaler
145  // We do this in earth frame to allow for rover leaning over in hard corners
146  float yaw_rate_earth = ToDeg(_ahrs.get_yaw_rate_earth());
147  if (_reverse) {
148  yaw_rate_earth *= -1.0f;
149  }
150  float rate_error = (desired_rate - yaw_rate_earth) * scaler;
151 
152  // Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
153  // No conversion is required for K_D
154  float ki_rate = _K_I * _tau * 45.0f;
155  float kp_ff = MAX((_K_P - _K_I * _tau) * _tau - _K_D , 0) * 45.0f;
156  float k_ff = _K_FF * 45.0f;
157  float delta_time = (float)dt * 0.001f;
158 
159  // Multiply yaw rate error by _ki_rate and integrate
160  // Don't integrate if in stabilize mode as the integrator will wind up against the pilots inputs
161  if (ki_rate > 0 && speed >= _minspeed) {
162  // only integrate if gain and time step are positive.
163  if (dt > 0) {
164  float integrator_delta = rate_error * ki_rate * delta_time * scaler;
165  // prevent the integrator from increasing if steering defln demand is above the upper limit
166  if (_last_out < -45) {
167  integrator_delta = MAX(integrator_delta , 0);
168  } else if (_last_out > 45) {
169  // prevent the integrator from decreasing if steering defln demand is below the lower limit
170  integrator_delta = MIN(integrator_delta, 0);
171  }
172  _pid_info.I += integrator_delta;
173  }
174  } else {
175  _pid_info.I = 0;
176  }
177 
178  // Scale the integration limit
179  float intLimScaled = _imax * 0.01f;
180 
181  // Constrain the integrator state
182  _pid_info.I = constrain_float(_pid_info.I, -intLimScaled, intLimScaled);
183 
184  _pid_info.D = rate_error * _K_D * 4.0f;
185  _pid_info.P = (ToRad(desired_rate) * kp_ff) * scaler;
186  _pid_info.FF = (ToRad(desired_rate) * k_ff) * scaler;
187 
188  // Calculate the demanded control surface deflection
190 
191  float derate_constraint = 4500;
192 
193  // Calculate required constrain based on speed
194  if (!is_zero(_deratespeed) && speed > _deratespeed) {
195  derate_constraint = 4500 - (speed - _deratespeed) * _deratefactor * 100;
196  if (derate_constraint < _mindegree) {
197  derate_constraint = _mindegree;
198  }
199  }
200 
201  // Convert to centi-degrees and constrain
202  return constrain_float(_last_out * 100, -derate_constraint, derate_constraint);
203 }
204 
205 
206 /*
207  lateral acceleration controller. Returns servo value -4500 to 4500
208  given a desired lateral acceleration
209 */
211 {
212  float speed = _ahrs.groundspeed();
213  if (speed < _minspeed) {
214  // assume a minimum speed. This reduces osciallations when first starting to move
215  speed = _minspeed;
216  }
217 
218  // Calculate the desired steering rate given desired_accel and speed
219  float desired_rate = ToDeg(desired_accel / speed);
220  if (_reverse) {
221  desired_rate *= -1;
222  }
223  return get_steering_out_rate(desired_rate);
224 }
225 
226 /*
227  return a steering servo value from -4500 to 4500 given an angular
228  steering error in centidegrees.
229 */
231 {
232  if (_tau < 0.1f) {
233  _tau = 0.1f;
234  }
235 
236  // Calculate the desired steering rate (deg/sec) from the angle error
237  float desired_rate = angle_err * 0.01f / _tau;
238 
239  return get_steering_out_rate(desired_rate);
240 }
241 
243 {
244  _pid_info.I = 0;
245 }
246 
#define ToRad(x)
Definition: AP_Common.h:53
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_yaw_rate_earth(void) const
Definition: AP_AHRS.h:206
#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
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint32_t millis()
Definition: system.cpp:157
int32_t get_steering_out_lat_accel(float desired_accel)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
DataFlash_Class::PID_Info _pid_info
int32_t get_steering_out_rate(float desired_rate)
static const struct AP_Param::GroupInfo var_info[]
float groundspeed(void)
Definition: AP_AHRS.h:359
int32_t get_steering_out_angle_error(int32_t angle_err)
#define AP_GROUPEND
Definition: AP_Param.h:121