Path: blob/master/libraries/APM_Control/AP_FW_Controller.cpp
4232 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14// Code by Jon Challinger15// Modified by Paul Riseborough16//171819#include "AP_FW_Controller.h"20#include <AP_AHRS/AP_AHRS.h>21#include <AP_Scheduler/AP_Scheduler.h>22#include <GCS_MAVLink/GCS.h>2324AP_FW_Controller::AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults, AP_AutoTune::ATType _autotune_type)25: aparm(parms),26rate_pid(defaults),27autotune_type(_autotune_type)28{29rate_pid.set_slew_limit_scale(45);30}3132/*33AC_PID based rate controller34*/35float AP_FW_Controller::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode)36{37const float dt = AP::scheduler().get_loop_period_s();3839const float eas2tas = AP::ahrs().get_EAS2TAS();40bool limit_I = fabsf(_last_out) >= 45;41const float rate = get_measured_rate();42const float old_I = rate_pid.get_i();4344const bool underspeed = is_underspeed(aspeed);45if (underspeed) {46limit_I = true;47}4849// the PID elements are scaled by sq(scaler). To use an50// unmodified AC_PID object we scale the inputs (target and measurement)51//52// note that we run AC_PID in radians so that the normal scaling53// range for IMAX in AC_PID applies (usually an IMAX value less than 1.0)54rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate * scaler * scaler, dt, limit_I);5556if (underspeed) {57// when underspeed we lock the integrator58rate_pid.set_integrator(old_I);59}6061// FF and DFF should be scaled by scaler/eas2tas, but since we have scaled62// the AC_PID target above by scaler*scaler we need to instead63// divide by scaler*eas2tas to get the right scaling64const float ff = degrees(ff_scale * rate_pid.get_ff_component() / (scaler * eas2tas));65const float dff = degrees(ff_scale * rate_pid.get_dff_component() / (scaler * eas2tas));66ff_scale = 1.0;6768if (disable_integrator) {69rate_pid.reset_I();70}7172// convert AC_PID info object to same scale as old controller73_pid_info = rate_pid.get_pid_info();74auto &pinfo = _pid_info;7576const float deg_scale = degrees(1);77pinfo.FF = ff;78pinfo.P *= deg_scale;79pinfo.I *= deg_scale;80pinfo.D *= deg_scale;81pinfo.DFF = dff;8283// fix the logged target and actual values to not have the scalers applied84pinfo.target = desired_rate;85pinfo.actual = degrees(rate);8687// sum components88float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF;89if (ground_mode) {90// when on ground suppress D and half P term to prevent oscillations91out -= pinfo.D + 0.5*pinfo.P;92}9394// remember the last output to trigger the I limit95_last_out = out;9697if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) {98// let autotune have a go at the values99autotune->update(pinfo, scaler, angle_err_deg);100}101102// output is scaled to notional centidegrees of deflection103return constrain_float(out * 100, -4500, 4500);104}105106/*107Function returns an equivalent control surface deflection in centi-degrees in the range from -4500 to 4500108*/109float AP_FW_Controller::get_rate_out(float desired_rate, float scaler)110{111return _get_rate_out(desired_rate, scaler, false, get_airspeed(), false);112}113114void AP_FW_Controller::reset_I()115{116rate_pid.reset_I();117}118119/*120reduce the integrator, used when we have a low scale factor in a quadplane hover121*/122void AP_FW_Controller::decay_I()123{124// this reduces integrator by 95% over 2s125_pid_info.I *= 0.995f;126rate_pid.set_integrator(rate_pid.get_i() * 0.995);127}128129/*130restore autotune gains131*/132void AP_FW_Controller::autotune_restore(void)133{134if (autotune != nullptr) {135autotune->stop();136}137}138139/*140start an autotune141*/142void AP_FW_Controller::autotune_start(void)143{144if (autotune == nullptr) {145autotune = NEW_NOTHROW AP_AutoTune(gains, autotune_type, aparm, rate_pid);146if (autotune == nullptr) {147if (!failed_autotune_alloc) {148GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed %s allocation", AP_AutoTune::axis_string(autotune_type));149}150failed_autotune_alloc = true;151}152}153if (autotune != nullptr) {154autotune->start();155}156}157158159160