Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/APM_Control/AP_FW_Controller.cpp
4232 views
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
// Code by Jon Challinger
16
// Modified by Paul Riseborough
17
//
18
19
20
#include "AP_FW_Controller.h"
21
#include <AP_AHRS/AP_AHRS.h>
22
#include <AP_Scheduler/AP_Scheduler.h>
23
#include <GCS_MAVLink/GCS.h>
24
25
AP_FW_Controller::AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults, AP_AutoTune::ATType _autotune_type)
26
: aparm(parms),
27
rate_pid(defaults),
28
autotune_type(_autotune_type)
29
{
30
rate_pid.set_slew_limit_scale(45);
31
}
32
33
/*
34
AC_PID based rate controller
35
*/
36
float AP_FW_Controller::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode)
37
{
38
const float dt = AP::scheduler().get_loop_period_s();
39
40
const float eas2tas = AP::ahrs().get_EAS2TAS();
41
bool limit_I = fabsf(_last_out) >= 45;
42
const float rate = get_measured_rate();
43
const float old_I = rate_pid.get_i();
44
45
const bool underspeed = is_underspeed(aspeed);
46
if (underspeed) {
47
limit_I = true;
48
}
49
50
// the PID elements are scaled by sq(scaler). To use an
51
// unmodified AC_PID object we scale the inputs (target and measurement)
52
//
53
// note that we run AC_PID in radians so that the normal scaling
54
// range for IMAX in AC_PID applies (usually an IMAX value less than 1.0)
55
rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate * scaler * scaler, dt, limit_I);
56
57
if (underspeed) {
58
// when underspeed we lock the integrator
59
rate_pid.set_integrator(old_I);
60
}
61
62
// FF and DFF should be scaled by scaler/eas2tas, but since we have scaled
63
// the AC_PID target above by scaler*scaler we need to instead
64
// divide by scaler*eas2tas to get the right scaling
65
const float ff = degrees(ff_scale * rate_pid.get_ff_component() / (scaler * eas2tas));
66
const float dff = degrees(ff_scale * rate_pid.get_dff_component() / (scaler * eas2tas));
67
ff_scale = 1.0;
68
69
if (disable_integrator) {
70
rate_pid.reset_I();
71
}
72
73
// convert AC_PID info object to same scale as old controller
74
_pid_info = rate_pid.get_pid_info();
75
auto &pinfo = _pid_info;
76
77
const float deg_scale = degrees(1);
78
pinfo.FF = ff;
79
pinfo.P *= deg_scale;
80
pinfo.I *= deg_scale;
81
pinfo.D *= deg_scale;
82
pinfo.DFF = dff;
83
84
// fix the logged target and actual values to not have the scalers applied
85
pinfo.target = desired_rate;
86
pinfo.actual = degrees(rate);
87
88
// sum components
89
float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF;
90
if (ground_mode) {
91
// when on ground suppress D and half P term to prevent oscillations
92
out -= pinfo.D + 0.5*pinfo.P;
93
}
94
95
// remember the last output to trigger the I limit
96
_last_out = out;
97
98
if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) {
99
// let autotune have a go at the values
100
autotune->update(pinfo, scaler, angle_err_deg);
101
}
102
103
// output is scaled to notional centidegrees of deflection
104
return constrain_float(out * 100, -4500, 4500);
105
}
106
107
/*
108
Function returns an equivalent control surface deflection in centi-degrees in the range from -4500 to 4500
109
*/
110
float AP_FW_Controller::get_rate_out(float desired_rate, float scaler)
111
{
112
return _get_rate_out(desired_rate, scaler, false, get_airspeed(), false);
113
}
114
115
void AP_FW_Controller::reset_I()
116
{
117
rate_pid.reset_I();
118
}
119
120
/*
121
reduce the integrator, used when we have a low scale factor in a quadplane hover
122
*/
123
void AP_FW_Controller::decay_I()
124
{
125
// this reduces integrator by 95% over 2s
126
_pid_info.I *= 0.995f;
127
rate_pid.set_integrator(rate_pid.get_i() * 0.995);
128
}
129
130
/*
131
restore autotune gains
132
*/
133
void AP_FW_Controller::autotune_restore(void)
134
{
135
if (autotune != nullptr) {
136
autotune->stop();
137
}
138
}
139
140
/*
141
start an autotune
142
*/
143
void AP_FW_Controller::autotune_start(void)
144
{
145
if (autotune == nullptr) {
146
autotune = NEW_NOTHROW AP_AutoTune(gains, autotune_type, aparm, rate_pid);
147
if (autotune == nullptr) {
148
if (!failed_autotune_alloc) {
149
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed %s allocation", AP_AutoTune::axis_string(autotune_type));
150
}
151
failed_autotune_alloc = true;
152
}
153
}
154
if (autotune != nullptr) {
155
autotune->start();
156
}
157
}
158
159
160