Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/APM_Control/AP_AutoTune.cpp
Views: 1798
/*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*/1415/**16The strategy for roll/pitch autotune is to give the user a AUTOTUNE17flight mode which behaves just like FBWA, but does automatic18tuning.19*/2021#include "AP_AutoTune.h"2223#include <AP_Common/AP_Common.h>24#include <AP_HAL/AP_HAL.h>25#include <AP_Logger/AP_Logger.h>26#include <AP_Math/AP_Math.h>27#include <AC_PID/AC_PID.h>28#include <AP_Scheduler/AP_Scheduler.h>29#include <GCS_MAVLink/GCS.h>30#include <AP_InertialSensor/AP_InertialSensor.h>3132extern const AP_HAL::HAL& hal;3334// step size for changing FF gains, percentage35#define AUTOTUNE_INCREASE_FF_STEP 1236#define AUTOTUNE_DECREASE_FF_STEP 153738// limits on IMAX39#define AUTOTUNE_MIN_IMAX 0.440#define AUTOTUNE_MAX_IMAX 0.94142// ratio of I to P43#define AUTOTUNE_I_RATIO 0.754445// time constant of rate trim loop46#define TRIM_TCONST 1.0f4748// constructor49AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,50const AP_FixedWing &parms,51AC_PID &_rpid) :52current(_gains),53rpid(_rpid),54type(_type),55aparm(parms),56ff_filter(2)57{}5859#if CONFIG_HAL_BOARD == HAL_BOARD_SITL60#include <stdio.h>61# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)62#else63# define Debug(fmt, args ...)64#endif6566/*67auto-tuning table. This table gives the starting values for key68tuning parameters based on a user chosen AUTOTUNE_LEVEL parameter69from 1 to 10. Level 1 is a very soft tune. Level 10 is a very70aggressive tune.71Level 0 means use the existing RMAX and TCONST parameters72*/73static const struct {74float tau;75float rmax;76} tuning_table[] = {77{ 1.00, 20 }, // level 178{ 0.90, 30 }, // level 279{ 0.80, 40 }, // level 380{ 0.70, 50 }, // level 481{ 0.60, 60 }, // level 582{ 0.50, 75 }, // level 683{ 0.30, 90 }, // level 784{ 0.2, 120 }, // level 885{ 0.15, 160 }, // level 986{ 0.1, 210 }, // level 1087{ 0.1, 300 }, // (yes, it goes to 11)88};8990/*91start an autotune session92*/93void AP_AutoTune::start(void)94{95running = true;96state = ATState::IDLE;9798current = restore = last_save = get_gains();99100// do first update of rmax and tau now101update_rmax();102103dt = AP::scheduler().get_loop_period_s();104105rpid.kIMAX().set(constrain_float(rpid.kIMAX(), AUTOTUNE_MIN_IMAX, AUTOTUNE_MAX_IMAX));106107// use 0.75Hz filters on the actuator, rate and target to reduce impact of noise108actuator_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 0.75);109rate_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 0.75);110111// target filter is a bit broader112target_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 4);113114ff_filter.reset();115actuator_filter.reset();116rate_filter.reset();117D_limit = 0;118P_limit = 0;119ff_count = 0;120D_set_ms = 0;121P_set_ms = 0;122done_count = 0;123124if (!is_positive(rpid.slew_limit())) {125// we must have a slew limit, default to 150 deg/s126rpid.slew_limit().set_and_save(150);127}128129if (current.FF < 0.01) {130// don't allow for zero FF131current.FF = 0.01;132rpid.ff().set(current.FF);133}134135Debug("START FF -> %.3f\n", rpid.ff().get());136}137138/*139called when we change state to see if we should change gains140*/141void AP_AutoTune::stop(void)142{143if (running) {144running = false;145if (is_positive(D_limit) && is_positive(P_limit)) {146save_gains();147} else {148restore_gains();149}150}151}152153const char *AP_AutoTune::axis_string(void) const154{155switch (type) {156case AUTOTUNE_ROLL:157return "Roll";158case AUTOTUNE_PITCH:159return "Pitch";160case AUTOTUNE_YAW:161return "Yaw";162}163return "";164}165166/*167one update cycle of the autotuner168*/169void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)170{171if (!running) {172return;173}174175// see what state we are in176ATState new_state = state;177const float desired_rate = target_filter.apply(pinfo.target);178179// filter actuator without I term so we can take ratios without180// accounting for trim offsets. We first need to include the I and181// clip to 45 degrees to get the right value of the real surface182const float clipped_actuator = constrain_float(pinfo.FF + pinfo.P + pinfo.D + pinfo.DFF + pinfo.I, -45, 45) - pinfo.I;183const float actuator = actuator_filter.apply(clipped_actuator);184const float actual_rate = rate_filter.apply(pinfo.actual);185186max_actuator = MAX(max_actuator, actuator);187min_actuator = MIN(min_actuator, actuator);188max_rate = MAX(max_rate, actual_rate);189min_rate = MIN(min_rate, actual_rate);190max_target = MAX(max_target, desired_rate);191min_target = MIN(min_target, desired_rate);192max_P = MAX(max_P, fabsf(pinfo.P));193max_D = MAX(max_D, fabsf(pinfo.D));194min_Dmod = MIN(min_Dmod, pinfo.Dmod);195max_Dmod = MAX(max_Dmod, pinfo.Dmod);196197// update the P and D slew rates, using P and D values from before Dmod was applied198const float slew_limit_scale = 45.0 / degrees(1);199slew_limit_max = rpid.slew_limit();200slew_limit_tau = 1.0;201slew_limiter_P.modifier((pinfo.P/pinfo.Dmod)*slew_limit_scale, dt);202slew_limiter_D.modifier((pinfo.D/pinfo.Dmod)*slew_limit_scale, dt);203204// remember maximum slew rates for this cycle205max_SRate_P = MAX(max_SRate_P, slew_limiter_P.get_slew_rate());206max_SRate_D = MAX(max_SRate_D, slew_limiter_D.get_slew_rate());207208float att_limit_deg = 0;209switch (type) {210case AUTOTUNE_ROLL:211att_limit_deg = aparm.roll_limit;212break;213case AUTOTUNE_PITCH:214att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;215break;216case AUTOTUNE_YAW:217// arbitrary value for yaw angle218att_limit_deg = 20;219break;220}221222223// thresholds for when we consider an event to start and end224const float rate_threshold1 = 0.4 * MIN(att_limit_deg / current.tau.get(), current.rmax_pos);225const float rate_threshold2 = 0.25 * rate_threshold1;226bool in_att_demand = fabsf(angle_err_deg) >= 0.3 * att_limit_deg;227228switch (state) {229case ATState::IDLE:230if (desired_rate > rate_threshold1 && in_att_demand) {231new_state = ATState::DEMAND_POS;232} else if (desired_rate < -rate_threshold1 && in_att_demand) {233new_state = ATState::DEMAND_NEG;234}235break;236case ATState::DEMAND_POS:237if (desired_rate < rate_threshold2) {238new_state = ATState::IDLE;239}240break;241case ATState::DEMAND_NEG:242if (desired_rate > -rate_threshold2) {243new_state = ATState::IDLE;244}245break;246}247248const uint32_t now = AP_HAL::millis();249250#if HAL_LOGGING_ENABLED251if (now - last_log_ms >= 40) {252// log at 25Hz253const struct log_ATRP pkt {254LOG_PACKET_HEADER_INIT(LOG_ATRP_MSG),255time_us : AP_HAL::micros64(),256type : uint8_t(type),257state: uint8_t(new_state),258actuator : actuator,259P_slew : max_SRate_P,260D_slew : max_SRate_D,261FF_single: FF_single,262FF: current.FF,263P: current.P,264I: current.I,265D: current.D,266action: uint8_t(action),267rmax: float(current.rmax_pos.get()),268tau: current.tau.get()269};270AP::logger().WriteBlock(&pkt, sizeof(pkt));271last_log_ms = now;272}273#endif274275if (new_state == state) {276if (state == ATState::IDLE &&277now - state_enter_ms > 500 &&278max_Dmod < 0.9) {279// we've been oscillating while idle, reduce P or D280const float slew_sum = max_SRate_P + max_SRate_D;281const float gain_mul = 0.5;282current.P *= linear_interpolate(gain_mul, 1.0,283max_SRate_P,284slew_sum, 0);285current.D *= linear_interpolate(gain_mul, 1.0,286max_SRate_D,287slew_sum, 0);288rpid.kP().set(current.P);289rpid.kD().set(current.D);290action = Action::IDLE_LOWER_PD;291P_limit = MIN(P_limit, current.P);292D_limit = MIN(D_limit, current.D);293state_change(state);294}295return;296}297298if (new_state != ATState::IDLE) {299// starting an event300min_actuator = max_actuator = min_rate = max_rate = 0;301state_enter_ms = now;302state = new_state;303return;304}305306if ((state == ATState::DEMAND_POS && max_rate < 0.01 * current.rmax_pos) ||307(state == ATState::DEMAND_NEG && min_rate > -0.01 * current.rmax_neg)) {308// we didn't get enough rate309action = Action::LOW_RATE;310state_change(ATState::IDLE);311return;312}313314if (now - state_enter_ms < 100) {315// not long enough sample316action = Action::SHORT;317state_change(ATState::IDLE);318return;319}320321// we've finished an event. calculate the single-event FF value322if (state == ATState::DEMAND_POS) {323FF_single = max_actuator / (max_rate * scaler);324} else {325FF_single = min_actuator / (min_rate * scaler);326}327328// apply median filter329float FF = ff_filter.apply(FF_single);330ff_count++;331332const float old_FF = rpid.ff();333334// limit size of change in FF335FF = constrain_float(FF,336old_FF*(1-AUTOTUNE_DECREASE_FF_STEP*0.01),337old_FF*(1+AUTOTUNE_INCREASE_FF_STEP*0.01));338339// adjust P and D340float D = rpid.kD();341float P = rpid.kP();342343if (ff_count == 1) {344// apply minimum D and P values345D = MAX(D, 0.0005);346P = MAX(P, 0.01);347} else if (ff_count == 4) {348// we got a good ff estimate, halve P ready to start raising D349P *= 0.5;350}351352// see if the slew limiter kicked in353if (min_Dmod < 1.0 && !is_positive(D_limit)) {354// oscillation, without D_limit set355if (max_P > 0.5 * max_D) {356// lower P and D to get us to a non-oscillating state357P *= 0.35;358D *= 0.75;359action = Action::LOWER_PD;360} else {361// set D limit to 30% of current D, remember D limit and start to work on P362D *= 0.3;363D_limit = D;364D_set_ms = now;365action = Action::LOWER_D;366GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sD: %.4f", axis_string(), D_limit);367}368} else if (min_Dmod < 1.0) {369// oscillation, with D_limit set370if (now - D_set_ms > 2000) {371// leave 2s for Dmod to settle after lowering D372if (max_D > 0.8 * max_P) {373// lower D limit some more374D *= 0.35;375D_limit = D;376D_set_ms = now;377action = Action::LOWER_D;378GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sD: %.4f", axis_string(), D_limit);379done_count = 0;380} else if (now - P_set_ms > 2500) {381if (is_positive(P_limit)) {382// if we've already got a P estimate then don't383// reduce as quickly, stopping small spikes at the384// later part of the tune from giving us a very385// low P gain386P *= 0.7;387} else {388P *= 0.35;389}390P_limit = P;391P_set_ms = now;392action = Action::LOWER_P;393done_count = 0;394GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sP: %.4f", axis_string(), P_limit);395}396}397} else if (ff_count < 4) {398// we don't have a good FF estimate yet, keep going399400} else if (!is_positive(D_limit)) {401/* we haven't detected D oscillation yet, keep raising D */402D *= 1.3;403action = Action::RAISE_D;404} else if (!is_positive(P_limit)) {405/* not oscillating, increase P gain */406P *= 1.3;407action = Action::RAISE_PD;408} else {409// after getting P_limit we consider the tune done when we410// have done 3 cycles without reducing P411if (done_count < 3) {412if (++done_count == 3) {413GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s: Finished", axis_string());414save_gains();415}416}417}418419rpid.ff().set(FF);420rpid.kP().set(P);421rpid.kD().set(D);422if (type == AUTOTUNE_ROLL) { // for roll set I = smaller of FF or P423rpid.kI().set(MIN(P, (FF / TRIM_TCONST)));424} else { // for pitch/yaw naturally damped axes) set I usually = FF to get 1 sec I closure425rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST)));426}427428// setup filters to be suitable for time constant and gyro filter429// filtering T can prevent P/D oscillation being seen, so allow the430// user to switch it off431if (!has_option(DISABLE_FLTT_UPDATE)) {432rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI));433}434rpid.filt_E_hz().set(0);435// filtering D at the same level as VTOL can allow unwanted oscillations to be seen,436// so allow the user to switch it off and select their own (usually lower) value437if (!has_option(DISABLE_FLTD_UPDATE)) {438rpid.filt_D_hz().set(AP::ins().get_gyro_filter_hz()*0.5);439}440441current.FF = FF;442current.P = P;443current.I = rpid.kI().get();444current.D = D;445446Debug("FPID=(%.3f, %.3f, %.3f, %.3f) Dmod=%.2f\n",447rpid.ff().get(),448rpid.kP().get(),449rpid.kI().get(),450rpid.kD().get(),451min_Dmod);452453// move rmax and tau towards target454update_rmax();455456state_change(new_state);457}458459/*460record a state change461*/462void AP_AutoTune::state_change(ATState new_state)463{464min_Dmod = 1;465max_Dmod = 0;466max_SRate_P = 1;467max_SRate_D = 1;468max_P = max_D = 0;469state = new_state;470state_enter_ms = AP_HAL::millis();471}472473/*474save a float if it has changed475*/476void AP_AutoTune::save_float_if_changed(AP_Float &v, float old_value)477{478if (!is_equal(old_value, v.get())) {479v.save();480}481}482483/*484save a int16_t if it has changed485*/486void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t old_value)487{488if (old_value != v.get()) {489v.save();490}491}492493494/*495save a set of gains496*/497void AP_AutoTune::save_gains(void)498{499const auto &v = last_save;500save_float_if_changed(current.tau, v.tau);501save_int16_if_changed(current.rmax_pos, v.rmax_pos);502save_int16_if_changed(current.rmax_neg, v.rmax_neg);503save_float_if_changed(rpid.ff(), v.FF);504save_float_if_changed(rpid.kP(), v.P);505save_float_if_changed(rpid.kI(), v.I);506save_float_if_changed(rpid.kD(), v.D);507save_float_if_changed(rpid.kIMAX(), v.IMAX);508save_float_if_changed(rpid.filt_T_hz(), v.flt_T);509save_float_if_changed(rpid.filt_E_hz(), v.flt_E);510save_float_if_changed(rpid.filt_D_hz(), v.flt_D);511last_save = get_gains();512}513514/*515get gains with PID components516*/517AP_AutoTune::ATGains AP_AutoTune::get_gains(void)518{519ATGains ret = current;520ret.FF = rpid.ff();521ret.P = rpid.kP();522ret.I = rpid.kI();523ret.D = rpid.kD();524ret.IMAX = rpid.kIMAX();525ret.flt_T = rpid.filt_T_hz();526ret.flt_E = rpid.filt_E_hz();527ret.flt_D = rpid.filt_D_hz();528return ret;529}530531/*532set gains with PID components533*/534void AP_AutoTune::restore_gains(void)535{536current = restore;537rpid.ff().set(restore.FF);538rpid.kP().set(restore.P);539rpid.kI().set(restore.I);540rpid.kD().set(restore.D);541rpid.kIMAX().set(restore.IMAX);542rpid.filt_T_hz().set(restore.flt_T);543rpid.filt_E_hz().set(restore.flt_E);544rpid.filt_D_hz().set(restore.flt_D);545}546547/*548update RMAX and TAU parameters on each step. We move them gradually549towards the target to allow for a user going straight to a level 10550tune while starting with a poorly tuned plane551*/552void AP_AutoTune::update_rmax(void)553{554uint8_t level = constrain_int32(aparm.autotune_level, 0, ARRAY_SIZE(tuning_table));555556int16_t target_rmax;557float target_tau;558559if (level == 0) {560// this level means to keep current values of RMAX and TCONST561target_rmax = constrain_float(current.rmax_pos, 20, 720);562target_tau = constrain_float(current.tau, 0.1, 2);563} else {564target_rmax = tuning_table[level-1].rmax;565target_tau = tuning_table[level-1].tau;566if (type == AUTOTUNE_PITCH) {567// 50% longer time constant on pitch568target_tau *= 1.5;569}570}571572if (level > 0 && is_positive(current.FF)) {573const float invtau = ((1.0f / target_tau) + (current.I / current.FF));574if (is_positive(invtau)) {575target_tau = MAX(target_tau,1.0f / invtau);576}577}578579if (current.rmax_pos == 0) {580// conservative initial value581current.rmax_pos.set(75);582}583// move RMAX by 20 deg/s per step584current.rmax_pos.set(constrain_int32(target_rmax,585current.rmax_pos.get()-20,586current.rmax_pos.get()+20));587588if (level != 0 || current.rmax_neg.get() == 0) {589current.rmax_neg.set(current.rmax_pos.get());590}591592// move tau by max 15% per loop593current.tau.set(constrain_float(target_tau,594current.tau*0.85,595current.tau*1.15));596}597598599