Path: blob/master/libraries/APM_Control/AP_AutoTune.cpp
9326 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*/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{155return axis_string(type);156}157158const char *AP_AutoTune::axis_string(ATType _type)159{160switch (_type) {161case AUTOTUNE_ROLL:162return "Roll";163case AUTOTUNE_PITCH:164return "Pitch";165case AUTOTUNE_YAW:166return "Yaw";167}168return "";169}170171/*172one update cycle of the autotuner173*/174void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)175{176if (!running) {177return;178}179180// see what state we are in181ATState new_state = state;182const float desired_rate = target_filter.apply(pinfo.target);183184// filter actuator without I term so we can take ratios without185// accounting for trim offsets. We first need to include the I and186// clip to 45 degrees to get the right value of the real surface187const float clipped_actuator = constrain_float(pinfo.FF + pinfo.P + pinfo.D + pinfo.DFF + pinfo.I, -45, 45) - pinfo.I;188const float actuator = actuator_filter.apply(clipped_actuator);189const float actual_rate = rate_filter.apply(pinfo.actual);190191max_actuator = MAX(max_actuator, actuator);192min_actuator = MIN(min_actuator, actuator);193max_rate = MAX(max_rate, actual_rate);194min_rate = MIN(min_rate, actual_rate);195max_target = MAX(max_target, desired_rate);196min_target = MIN(min_target, desired_rate);197max_P = MAX(max_P, fabsf(pinfo.P));198max_D = MAX(max_D, fabsf(pinfo.D));199min_Dmod = MIN(min_Dmod, pinfo.Dmod);200max_Dmod = MAX(max_Dmod, pinfo.Dmod);201202// update the P and D slew rates, using P and D values from before Dmod was applied203const float slew_limit_scale = 45.0 / degrees(1);204slew_limit_max = rpid.slew_limit();205slew_limit_tau = 1.0;206slew_limiter_P.modifier((pinfo.P/pinfo.Dmod)*slew_limit_scale, dt);207slew_limiter_D.modifier((pinfo.D/pinfo.Dmod)*slew_limit_scale, dt);208209// remember maximum slew rates for this cycle210max_SRate_P = MAX(max_SRate_P, slew_limiter_P.get_slew_rate());211max_SRate_D = MAX(max_SRate_D, slew_limiter_D.get_slew_rate());212213float att_limit_deg = 0;214switch (type) {215case AUTOTUNE_ROLL:216att_limit_deg = aparm.roll_limit;217break;218case AUTOTUNE_PITCH:219att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;220break;221case AUTOTUNE_YAW:222// arbitrary value for yaw angle223att_limit_deg = 20;224break;225}226227228// thresholds for when we consider an event to start and end229const float rate_threshold1 = 0.4 * MIN(att_limit_deg / current.tau.get(), current.rmax_pos);230const float rate_threshold2 = 0.25 * rate_threshold1;231bool in_att_demand = fabsf(angle_err_deg) >= 0.3 * att_limit_deg;232233switch (state) {234case ATState::IDLE:235if (desired_rate > rate_threshold1 && in_att_demand) {236new_state = ATState::DEMAND_POS;237} else if (desired_rate < -rate_threshold1 && in_att_demand) {238new_state = ATState::DEMAND_NEG;239}240break;241case ATState::DEMAND_POS:242if (desired_rate < rate_threshold2) {243new_state = ATState::IDLE;244}245break;246case ATState::DEMAND_NEG:247if (desired_rate > -rate_threshold2) {248new_state = ATState::IDLE;249}250break;251}252253const uint32_t now = AP_HAL::millis();254255#if HAL_LOGGING_ENABLED256if (now - last_log_ms >= 40) {257// log at 25Hz258const struct log_ATRP pkt {259LOG_PACKET_HEADER_INIT(LOG_ATRP_MSG),260time_us : AP_HAL::micros64(),261type : uint8_t(type),262state: uint8_t(new_state),263actuator : actuator,264P_slew : max_SRate_P,265D_slew : max_SRate_D,266FF_single: FF_single,267FF: current.FF,268P: current.P,269I: current.I,270D: current.D,271action: uint8_t(action),272rmax: float(current.rmax_pos.get()),273tau: current.tau.get()274};275AP::logger().WriteBlock(&pkt, sizeof(pkt));276last_log_ms = now;277}278#endif279280if (new_state == state) {281if (state == ATState::IDLE &&282now - state_enter_ms > 500 &&283max_Dmod < 0.9) {284// we've been oscillating while idle, reduce P or D285const float slew_sum = max_SRate_P + max_SRate_D;286const float gain_mul = 0.5;287current.P *= linear_interpolate(gain_mul, 1.0,288max_SRate_P,289slew_sum, 0);290current.D *= linear_interpolate(gain_mul, 1.0,291max_SRate_D,292slew_sum, 0);293rpid.kP().set(current.P);294rpid.kD().set(current.D);295action = Action::IDLE_LOWER_PD;296P_limit = MIN(P_limit, current.P);297D_limit = MIN(D_limit, current.D);298state_change(state);299}300return;301}302303if (new_state != ATState::IDLE) {304// starting an event305min_actuator = max_actuator = min_rate = max_rate = 0;306state_enter_ms = now;307state = new_state;308return;309}310311if ((state == ATState::DEMAND_POS && max_rate < 0.01 * current.rmax_pos) ||312(state == ATState::DEMAND_NEG && min_rate > -0.01 * current.rmax_neg)) {313// we didn't get enough rate314action = Action::LOW_RATE;315state_change(ATState::IDLE);316return;317}318319if (now - state_enter_ms < 100) {320// not long enough sample321action = Action::SHORT;322state_change(ATState::IDLE);323return;324}325326// we've finished an event. calculate the single-event FF value327if (state == ATState::DEMAND_POS) {328FF_single = max_actuator / (max_rate * scaler);329} else {330FF_single = min_actuator / (min_rate * scaler);331}332333// apply median filter334float FF = ff_filter.apply(FF_single);335ff_count++;336337const float old_FF = rpid.ff();338339// limit size of change in FF340FF = constrain_float(FF,341old_FF*(1-AUTOTUNE_DECREASE_FF_STEP*0.01),342old_FF*(1+AUTOTUNE_INCREASE_FF_STEP*0.01));343344// adjust P and D345float D = rpid.kD();346float P = rpid.kP();347348if (ff_count == 1) {349// apply minimum D and P values350D = MAX(D, 0.0005);351P = MAX(P, 0.01);352} else if (ff_count == 4) {353// we got a good ff estimate, halve P ready to start raising D354P *= 0.5;355}356357// see if the slew limiter kicked in358if (min_Dmod < 1.0 && !is_positive(D_limit)) {359// oscillation, without D_limit set360if (max_P > 0.5 * max_D) {361// lower P and D to get us to a non-oscillating state362P *= 0.35;363D *= 0.75;364action = Action::LOWER_PD;365} else {366// set D limit to 30% of current D, remember D limit and start to work on P367D *= 0.3;368D_limit = D;369D_set_ms = now;370action = Action::LOWER_D;371GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sD: %.4f", axis_string(), D_limit);372}373} else if (min_Dmod < 1.0) {374// oscillation, with D_limit set375if (now - D_set_ms > 2000) {376// leave 2s for Dmod to settle after lowering D377if (max_D > 0.8 * max_P) {378// lower D limit some more379D *= 0.35;380D_limit = D;381D_set_ms = now;382action = Action::LOWER_D;383GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sD: %.4f", axis_string(), D_limit);384done_count = 0;385} else if (now - P_set_ms > 2500) {386if (is_positive(P_limit)) {387// if we've already got a P estimate then don't388// reduce as quickly, stopping small spikes at the389// later part of the tune from giving us a very390// low P gain391P *= 0.7;392} else {393P *= 0.35;394}395P_limit = P;396P_set_ms = now;397action = Action::LOWER_P;398done_count = 0;399GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sP: %.4f", axis_string(), P_limit);400}401}402} else if (ff_count < 4) {403// we don't have a good FF estimate yet, keep going404405} else if (!is_positive(D_limit)) {406/* we haven't detected D oscillation yet, keep raising D */407D *= 1.3;408action = Action::RAISE_D;409} else if (!is_positive(P_limit)) {410/* not oscillating, increase P gain */411P *= 1.3;412action = Action::RAISE_PD;413} else {414// after getting P_limit we consider the tune done when we415// have done 3 cycles without reducing P416if (done_count < 3) {417if (++done_count == 3) {418GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s: Finished", axis_string());419save_gains();420}421}422}423424rpid.ff().set(FF);425rpid.kP().set(P);426rpid.kD().set(D);427if (type == AUTOTUNE_ROLL) { // for roll set I = smaller of FF or P428rpid.kI().set(MIN(P, (FF / TRIM_TCONST)));429} else { // for pitch/yaw naturally damped axes) set I usually = FF to get 1 sec I closure430rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST)));431}432433// setup filters to be suitable for time constant and gyro filter434// filtering T can prevent P/D oscillation being seen, so allow the435// user to switch it off436if (!has_option(DISABLE_FLTT_UPDATE)) {437rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI));438}439rpid.filt_E_hz().set(0);440// filtering D at the same level as VTOL can allow unwanted oscillations to be seen,441// so allow the user to switch it off and select their own (usually lower) value442if (!has_option(DISABLE_FLTD_UPDATE)) {443rpid.filt_D_hz().set(AP::ins().get_gyro_filter_hz()*0.5);444}445446current.FF = FF;447current.P = P;448current.I = rpid.kI().get();449current.D = D;450451Debug("FPID=(%.3f, %.3f, %.3f, %.3f) Dmod=%.2f\n",452rpid.ff().get(),453rpid.kP().get(),454rpid.kI().get(),455rpid.kD().get(),456min_Dmod);457458// move rmax and tau towards target459update_rmax();460461state_change(new_state);462}463464/*465record a state change466*/467void AP_AutoTune::state_change(ATState new_state)468{469min_Dmod = 1;470max_Dmod = 0;471max_SRate_P = 1;472max_SRate_D = 1;473max_P = max_D = 0;474state = new_state;475state_enter_ms = AP_HAL::millis();476}477478/*479save a float if it has changed480*/481void AP_AutoTune::save_float_if_changed(AP_Float &v, float old_value)482{483if (!is_equal(old_value, v.get())) {484v.save();485}486}487488/*489save a int16_t if it has changed490*/491void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t old_value)492{493if (old_value != v.get()) {494v.save();495}496}497498499/*500save a set of gains501*/502void AP_AutoTune::save_gains(void)503{504const auto &v = last_save;505save_float_if_changed(current.tau, v.tau);506save_int16_if_changed(current.rmax_pos, v.rmax_pos);507save_int16_if_changed(current.rmax_neg, v.rmax_neg);508save_float_if_changed(rpid.ff(), v.FF);509save_float_if_changed(rpid.kP(), v.P);510save_float_if_changed(rpid.kI(), v.I);511save_float_if_changed(rpid.kD(), v.D);512save_float_if_changed(rpid.kIMAX(), v.IMAX);513save_float_if_changed(rpid.filt_T_hz(), v.flt_T);514save_float_if_changed(rpid.filt_E_hz(), v.flt_E);515save_float_if_changed(rpid.filt_D_hz(), v.flt_D);516last_save = get_gains();517}518519/*520get gains with PID components521*/522AP_AutoTune::ATGains AP_AutoTune::get_gains(void)523{524ATGains ret = current;525ret.FF = rpid.ff();526ret.P = rpid.kP();527ret.I = rpid.kI();528ret.D = rpid.kD();529ret.IMAX = rpid.kIMAX();530ret.flt_T = rpid.filt_T_hz();531ret.flt_E = rpid.filt_E_hz();532ret.flt_D = rpid.filt_D_hz();533return ret;534}535536/*537set gains with PID components538*/539void AP_AutoTune::restore_gains(void)540{541current = restore;542rpid.ff().set(restore.FF);543rpid.kP().set(restore.P);544rpid.kI().set(restore.I);545rpid.kD().set(restore.D);546rpid.kIMAX().set(restore.IMAX);547rpid.filt_T_hz().set(restore.flt_T);548rpid.filt_E_hz().set(restore.flt_E);549rpid.filt_D_hz().set(restore.flt_D);550}551552/*553update RMAX and TAU parameters on each step. We move them gradually554towards the target to allow for a user going straight to a level 10555tune while starting with a poorly tuned plane556*/557void AP_AutoTune::update_rmax(void)558{559uint8_t level = constrain_int32(aparm.autotune_level, 0, ARRAY_SIZE(tuning_table));560561int16_t target_rmax;562float target_tau;563564if (level == 0) {565// this level means to keep current values of RMAX and TCONST566target_rmax = constrain_float(current.rmax_pos, 20, 720);567target_tau = constrain_float(current.tau, 0.1, 2);568} else {569target_rmax = tuning_table[level-1].rmax;570target_tau = tuning_table[level-1].tau;571if (type == AUTOTUNE_PITCH) {572// 50% longer time constant on pitch573target_tau *= 1.5;574}575}576577if (level > 0 && is_positive(current.FF)) {578const float invtau = ((1.0f / target_tau) + (current.I / current.FF));579if (is_positive(invtau)) {580target_tau = MAX(target_tau,1.0f / invtau);581}582}583584if (current.rmax_pos == 0) {585// conservative initial value586current.rmax_pos.set(75);587}588// move RMAX by 20 deg/s per step589current.rmax_pos.set(constrain_int32(target_rmax,590current.rmax_pos.get()-20,591current.rmax_pos.get()+20));592593if (level != 0 || current.rmax_neg.get() == 0) {594current.rmax_neg.set(current.rmax_pos.get());595}596597// move tau by max 15% per loop598current.tau.set(constrain_float(target_tau,599current.tau*0.85,600current.tau*1.15));601}602603604