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/AC_AutoTune/AC_AutoTune_Multi.cpp
Views: 1798
#include "AC_AutoTune_config.h"12#if AC_AUTOTUNE_ENABLED34#include "AC_AutoTune_Multi.h"56#include <AP_Logger/AP_Logger.h>7#include <AP_Scheduler/AP_Scheduler.h>8#include <GCS_MAVLink/GCS.h>910/*11* autotune support for multicopters12*13*14* Instructions:15* 1) Set up one flight mode switch position to be AltHold.16* 2) Set the Ch7 Opt or Ch8 Opt to AutoTune to allow you to turn the auto tuning on/off with the ch7 or ch8 switch.17* 3) Ensure the ch7 or ch8 switch is in the LOW position.18* 4) Wait for a calm day and go to a large open area.19* 5) Take off and put the vehicle into AltHold mode at a comfortable altitude.20* 6) Set the ch7/ch8 switch to the HIGH position to engage auto tuning:21* a) You will see it twitch about 20 degrees left and right for a few minutes, then it will repeat forward and back.22* b) Use the roll and pitch stick at any time to reposition the copter if it drifts away (it will use the original PID gains during repositioning and between tests).23* When you release the sticks it will continue auto tuning where it left off.24* c) Move the ch7/ch8 switch into the LOW position at any time to abandon the autotuning and return to the origin PIDs.25* d) Make sure that you do not have any trim set on your transmitter or the autotune may not get the signal that the sticks are centered.26* 7) When the tune completes the vehicle will change back to the original PID gains.27* 8) Put the ch7/ch8 switch into the LOW position then back to the HIGH position to test the tuned PID gains.28* 9) Put the ch7/ch8 switch into the LOW position to fly using the original PID gains.29* 10) If you are happy with the autotuned PID gains, leave the ch7/ch8 switch in the HIGH position, land and disarm to save the PIDs permanently.30* If you DO NOT like the new PIDS, switch ch7/ch8 LOW to return to the original PIDs. The gains will not be saved when you disarm31*32* What it's doing during each "twitch":33* a) invokes 90 deg/sec rate request34* b) records maximum "forward" roll rate and bounce back rate35* c) when copter reaches 20 degrees or 1 second has passed, it commands level36* d) tries to keep max rotation rate between 80% ~ 100% of requested rate (90deg/sec) by adjusting rate P37* e) increases rate D until the bounce back becomes greater than 10% of requested rate (90deg/sec)38* f) decreases rate D until the bounce back becomes less than 10% of requested rate (90deg/sec)39* g) increases rate P until the max rotate rate becomes greater than the request rate (90deg/sec)40* h) invokes a 20deg angle request on roll or pitch41* i) increases stab P until the maximum angle becomes greater than 110% of the requested angle (20deg)42* j) decreases stab P by 25%43*44*/4546#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 2000U // timeout for tuning mode's testing step4748#define AUTOTUNE_RD_STEP 0.05 // minimum increment when increasing/decreasing Rate D term49#define AUTOTUNE_RP_STEP 0.05 // minimum increment when increasing/decreasing Rate P term50#define AUTOTUNE_SP_STEP 0.05 // minimum increment when increasing/decreasing Stab P term51#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1 // I is set 10x smaller than P during testing52#define AUTOTUNE_PI_RATIO_FINAL 1.0 // I is set 1x P after testing53#define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1 // I is set 1x P after testing54#define AUTOTUNE_RD_MAX 0.200 // maximum Rate D value55#define AUTOTUNE_RLPF_MIN 1.0 // minimum Rate Yaw filter value56#define AUTOTUNE_RLPF_MAX 5.0 // maximum Rate Yaw filter value57#define AUTOTUNE_FLTE_MIN 2.5 // minimum Rate Yaw error filter value58#define AUTOTUNE_RP_MIN 0.01 // minimum Rate P value59#define AUTOTUNE_RP_MAX 2.0 // maximum Rate P value60#define AUTOTUNE_SP_MAX 40.0 // maximum Stab P value61#define AUTOTUNE_SP_MIN 0.5 // maximum Stab P value62#define AUTOTUNE_RP_ACCEL_MIN 4000.0 // Minimum acceleration for Roll and Pitch63#define AUTOTUNE_Y_ACCEL_MIN 1000.0 // Minimum acceleration for Yaw64#define AUTOTUNE_Y_FILT_FREQ 10.0 // Autotune filter frequency when testing Yaw65#define AUTOTUNE_D_UP_DOWN_MARGIN 0.2 // The margin below the target that we tune D in66#define AUTOTUNE_RD_BACKOFF 1.0 // Rate D gains are reduced to 50% of their maximum value discovered during tuning67#define AUTOTUNE_RP_BACKOFF 1.0 // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning68#define AUTOTUNE_SP_BACKOFF 0.9 // Stab P gains are reduced to 90% of their maximum value discovered during tuning69#define AUTOTUNE_ACCEL_RP_BACKOFF 1.0 // back off from maximum acceleration70#define AUTOTUNE_ACCEL_Y_BACKOFF 1.0 // back off from maximum acceleration7172// roll and pitch axes73#define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step74#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target min roll/pitch rate during AUTOTUNE_STEP_TWITCHING step7576// yaw axis77#define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step78#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step7980#define AUTOTUNE_TARGET_ANGLE_MAX_RP_SCALE 1.0 / 2.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step81#define AUTOTUNE_TARGET_ANGLE_MAX_Y_SCALE 1.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step82#define AUTOTUNE_TARGET_ANGLE_MIN_RP_SCALE 1.0 / 3.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step83#define AUTOTUNE_TARGET_ANGLE_MIN_Y_SCALE 1.0 / 6.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step84#define AUTOTUNE_ANGLE_ABORT_RP_SCALE 2.5 / 3.0 // maximum allowable angle during testing, as a fraction of angle_max85#define AUTOTUNE_ANGLE_MAX_Y_SCALE 1.0 // maximum allowable angle during testing, as a fraction of angle_max86#define AUTOTUNE_ANGLE_NEG_RP_SCALE 1.0 / 5.0 // maximum allowable angle during testing, as a fraction of angle_max8788// second table of user settable parameters for quadplanes, this89// allows us to go beyond the 64 parameter limit90const AP_Param::GroupInfo AC_AutoTune_Multi::var_info[] = {9192// @Param: AXES93// @DisplayName: Autotune axis bitmask94// @Description: 1-byte bitmap of axes to autotune95// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:YawD96// @User: Standard97AP_GROUPINFO("AXES", 1, AC_AutoTune_Multi, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT9899// @Param: AGGR100// @DisplayName: Autotune aggressiveness101// @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.102// @Range: 0.05 0.10103// @User: Standard104AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.075f),105106// @Param: MIN_D107// @DisplayName: AutoTune minimum D108// @Description: Defines the minimum D gain109// @Range: 0.0001 0.005110// @User: Standard111AP_GROUPINFO("MIN_D", 3, AC_AutoTune_Multi, min_d, 0.0005f),112113AP_GROUPEND114};115116// constructor117AC_AutoTune_Multi::AC_AutoTune_Multi()118{119tune_seq[0] = TUNE_COMPLETE;120AP_Param::setup_object_defaults(this, var_info);121}122123void AC_AutoTune_Multi::do_gcs_announcements()124{125const uint32_t now = AP_HAL::millis();126if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) {127return;128}129GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: %s %s %u%%", axis_string(), type_string(), (counter * (100/AUTOTUNE_SUCCESS_COUNT)));130announce_time = now;131}132133void AC_AutoTune_Multi::test_init()134{135twitch_test_init();136}137138void AC_AutoTune_Multi::test_run(AxisType test_axis, const float dir_sign)139{140twitch_test_run(test_axis, dir_sign);141}142143// backup_gains_and_initialise - store current gains as originals144// called before tuning starts to backup original gains145void AC_AutoTune_Multi::backup_gains_and_initialise()146{147AC_AutoTune::backup_gains_and_initialise();148149aggressiveness.set(constrain_float(aggressiveness, 0.05, 0.2));150151orig_bf_feedforward = attitude_control->get_bf_feedforward();152153// backup original pids and initialise tuned pid values154orig_roll_rp = attitude_control->get_rate_roll_pid().kP();155orig_roll_ri = attitude_control->get_rate_roll_pid().kI();156orig_roll_rd = attitude_control->get_rate_roll_pid().kD();157orig_roll_rff = attitude_control->get_rate_roll_pid().ff();158orig_roll_dff = attitude_control->get_rate_roll_pid().kDff();159orig_roll_fltt = attitude_control->get_rate_roll_pid().filt_T_hz();160orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit();161orig_roll_sp = attitude_control->get_angle_roll_p().kP();162orig_roll_accel = attitude_control->get_accel_roll_max_cdss();163tune_roll_rp = attitude_control->get_rate_roll_pid().kP();164tune_roll_rd = attitude_control->get_rate_roll_pid().kD();165tune_roll_sp = attitude_control->get_angle_roll_p().kP();166tune_roll_accel = attitude_control->get_accel_roll_max_cdss();167168orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();169orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();170orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();171orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();172orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff();173orig_pitch_fltt = attitude_control->get_rate_pitch_pid().filt_T_hz();174orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit();175orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();176orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();177tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP();178tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD();179tune_pitch_sp = attitude_control->get_angle_pitch_p().kP();180tune_pitch_accel = attitude_control->get_accel_pitch_max_cdss();181182orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();183orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();184orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();185orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();186orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff();187orig_yaw_fltt = attitude_control->get_rate_yaw_pid().filt_T_hz();188orig_yaw_smax = attitude_control->get_rate_yaw_pid().slew_limit();189orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();190orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();191orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();192tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP();193tune_yaw_rd = attitude_control->get_rate_yaw_pid().kD();194tune_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();195if (yaw_d_enabled() && is_zero(tune_yaw_rd)) {196tune_yaw_rd = min_d;197}198if (yaw_enabled() && is_zero(tune_yaw_rLPF)) {199tune_yaw_rLPF = AUTOTUNE_FLTE_MIN;200}201tune_yaw_sp = attitude_control->get_angle_yaw_p().kP();202tune_yaw_accel = attitude_control->get_accel_yaw_max_cdss();203204LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_INITIALISED);205}206207// load_orig_gains - set gains to their original values208// called by stop and failed functions209void AC_AutoTune_Multi::load_orig_gains()210{211attitude_control->bf_feedforward(orig_bf_feedforward);212if (roll_enabled()) {213if (!is_zero(orig_roll_rp)) {214attitude_control->get_rate_roll_pid().set_kP(orig_roll_rp);215attitude_control->get_rate_roll_pid().set_kI(orig_roll_ri);216attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd);217attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);218attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);219attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);220attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);221attitude_control->get_angle_roll_p().set_kP(orig_roll_sp);222attitude_control->set_accel_roll_max_cdss(orig_roll_accel);223}224}225if (pitch_enabled()) {226if (!is_zero(orig_pitch_rp)) {227attitude_control->get_rate_pitch_pid().set_kP(orig_pitch_rp);228attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_ri);229attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd);230attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);231attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);232attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);233attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);234attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp);235attitude_control->set_accel_pitch_max_cdss(orig_pitch_accel);236}237}238if (yaw_enabled() || yaw_d_enabled()) {239if (!is_zero(orig_yaw_rp)) {240attitude_control->get_rate_yaw_pid().set_kP(orig_yaw_rp);241attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_ri);242attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd);243attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);244attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);245attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF);246attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);247attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);248attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp);249attitude_control->set_accel_yaw_max_cdss(orig_yaw_accel);250}251}252}253254// load_tuned_gains - load tuned gains255void AC_AutoTune_Multi::load_tuned_gains()256{257if (!attitude_control->get_bf_feedforward()) {258attitude_control->bf_feedforward(true);259attitude_control->set_accel_roll_max_cdss(0.0);260attitude_control->set_accel_pitch_max_cdss(0.0);261}262if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {263attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);264attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);265attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);266attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);267attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);268attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);269attitude_control->set_accel_roll_max_cdss(tune_roll_accel);270}271if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {272attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);273attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);274attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);275attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);276attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);277attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);278attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel);279}280if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled())281|| ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_enabled())) && !is_zero(tune_yaw_rp)) {282attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);283attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);284if (yaw_d_enabled()) {285attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);286}287if (yaw_enabled()) {288attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);289}290attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);291attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);292attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);293attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel);294}295}296297// load_intra_test_gains - gains used between tests298// called during testing mode's update-gains step to set gains ahead of return-to-level step299void AC_AutoTune_Multi::load_intra_test_gains()300{301// we are restarting tuning so reset gains to tuning-start gains (i.e. low I term)302// sanity check the gains303attitude_control->bf_feedforward(true);304if (roll_enabled()) {305attitude_control->get_rate_roll_pid().set_kP(orig_roll_rp);306attitude_control->get_rate_roll_pid().set_kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);307attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd);308attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);309attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);310attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);311attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);312attitude_control->get_angle_roll_p().set_kP(orig_roll_sp);313}314if (pitch_enabled()) {315attitude_control->get_rate_pitch_pid().set_kP(orig_pitch_rp);316attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);317attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd);318attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);319attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);320attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);321attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);322attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp);323}324if (yaw_enabled() || yaw_d_enabled()) {325attitude_control->get_rate_yaw_pid().set_kP(orig_yaw_rp);326attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);327attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd);328attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);329attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);330attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);331attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);332attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF);333attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp);334}335}336337// load_test_gains - load the to-be-tested gains for a single axis338// called by control_attitude() just before it beings testing a gain (i.e. just before it twitches)339void AC_AutoTune_Multi::load_test_gains()340{341switch (axis) {342case AxisType::ROLL:343attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);344attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp * 0.01);345attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);346attitude_control->get_rate_roll_pid().set_ff(0.0);347attitude_control->get_rate_roll_pid().set_kDff(0.0);348attitude_control->get_rate_roll_pid().set_filt_T_hz(0.0);349attitude_control->get_rate_roll_pid().set_slew_limit(0.0);350attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);351break;352case AxisType::PITCH:353attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);354attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp * 0.01);355attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);356attitude_control->get_rate_pitch_pid().set_ff(0.0);357attitude_control->get_rate_pitch_pid().set_kDff(0.0);358attitude_control->get_rate_pitch_pid().set_filt_T_hz(0.0);359attitude_control->get_rate_pitch_pid().set_slew_limit(0.0);360attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);361break;362case AxisType::YAW:363case AxisType::YAW_D:364attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);365attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp * 0.01);366attitude_control->get_rate_yaw_pid().set_ff(0.0);367attitude_control->get_rate_yaw_pid().set_kDff(0.0);368if (axis == AxisType::YAW_D) {369attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);370} else {371attitude_control->get_rate_yaw_pid().set_kD(0.0);372attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);373}374attitude_control->get_rate_yaw_pid().set_filt_T_hz(0.0);375attitude_control->get_rate_yaw_pid().set_slew_limit(0.0);376attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);377break;378}379}380381// save_tuning_gains - save the final tuned gains for each axis382// save discovered gains to eeprom if autotuner is enabled (i.e. switch is in the high position)383void AC_AutoTune_Multi::save_tuning_gains()384{385// see if we successfully completed tuning of at least one axis386if (axes_completed == 0) {387return;388}389390if (!attitude_control->get_bf_feedforward()) {391attitude_control->bf_feedforward_save(true);392attitude_control->save_accel_roll_max_cdss(0.0);393attitude_control->save_accel_pitch_max_cdss(0.0);394}395396// sanity check the rate P values397if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {398// rate roll gains399attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);400attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);401attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);402attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);403attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);404attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);405attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);406attitude_control->get_rate_roll_pid().save_gains();407408// stabilize roll409attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);410attitude_control->get_angle_roll_p().save_gains();411412// acceleration roll413attitude_control->save_accel_roll_max_cdss(tune_roll_accel);414415// resave pids to originals in case the autotune is run again416orig_roll_rp = attitude_control->get_rate_roll_pid().kP();417orig_roll_ri = attitude_control->get_rate_roll_pid().kI();418orig_roll_rd = attitude_control->get_rate_roll_pid().kD();419orig_roll_rff = attitude_control->get_rate_roll_pid().ff();420orig_roll_dff = attitude_control->get_rate_roll_pid().kDff();421orig_roll_sp = attitude_control->get_angle_roll_p().kP();422orig_roll_accel = attitude_control->get_accel_roll_max_cdss();423}424425if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {426// rate pitch gains427attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);428attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);429attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);430attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);431attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);432attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);433attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);434attitude_control->get_rate_pitch_pid().save_gains();435436// stabilize pitch437attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);438attitude_control->get_angle_pitch_p().save_gains();439440// acceleration pitch441attitude_control->save_accel_pitch_max_cdss(tune_pitch_accel);442443// resave pids to originals in case the autotune is run again444orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();445orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();446orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();447orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();448orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff();449orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();450orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();451}452453if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled())454|| ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_enabled())) && !is_zero(tune_yaw_rp)) {455// rate yaw gains456attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);457attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);458attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);459attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);460attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);461attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);462if (yaw_d_enabled()) {463attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);464}465if (yaw_enabled()) {466attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);467}468attitude_control->get_rate_yaw_pid().save_gains();469470// stabilize yaw471attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);472attitude_control->get_angle_yaw_p().save_gains();473474// acceleration yaw475attitude_control->save_accel_yaw_max_cdss(tune_yaw_accel);476477// resave pids to originals in case the autotune is run again478orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();479orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();480orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();481orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();482orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff();483orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();484orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();485orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();486}487488// update GCS and log save gains event489update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);490LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SAVEDGAINS);491492reset();493}494495// report final gains for a given axis to GCS496void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const497{498switch (test_axis) {499case AxisType::ROLL:500report_axis_gains("Roll", tune_roll_rp, tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL, tune_roll_rd, tune_roll_sp, tune_roll_accel);501break;502case AxisType::PITCH:503report_axis_gains("Pitch", tune_pitch_rp, tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL, tune_pitch_rd, tune_pitch_sp, tune_pitch_accel);504break;505case AxisType::YAW:506report_axis_gains("Yaw(E)", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, 0, tune_yaw_sp, tune_yaw_accel);507break;508case AxisType::YAW_D:509report_axis_gains("Yaw(D)", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_sp, tune_yaw_accel);510break;511}512}513514// report gain formatting helper515void AC_AutoTune_Multi::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const516{517GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string);518GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.3f, I:%0.3f, D:%0.4f",axis_string,rate_P,rate_I,rate_D);519GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.3f, Max Accel:%0.0f",axis_string,angle_P,max_accel);520}521522// twitching_test_rate - twitching tests523// update min and max and test for end conditions524void AC_AutoTune_Multi::twitching_test_rate(float angle, float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max, float &meas_angle_min)525{526const uint32_t now = AP_HAL::millis();527528// capture maximum rate529if (rate > meas_rate_max) {530// the measurement is continuing to increase without stopping531meas_rate_max = rate;532meas_rate_min = rate;533meas_angle_min = angle;534}535536// capture minimum measurement after the measurement has peaked (aka "bounce back")537if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.25)) {538// the measurement is bouncing back539meas_rate_min = rate;540meas_angle_min = angle;541}542543// calculate early stopping time based on the time it takes to get to 63.21%544if (meas_rate_max < rate_target_max * 0.6321) {545// the measurement not reached the 63.21% threshold yet546step_time_limit_ms = (now - step_start_time_ms) * 3;547step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);548}549550if (meas_rate_max > rate_target_max) {551// the measured rate has passed the maximum target rate552step = UPDATE_GAINS;553}554555if (meas_rate_max - meas_rate_min > meas_rate_max * aggressiveness) {556// the measurement has passed 50% of the maximum rate and bounce back is larger than the threshold557step = UPDATE_GAINS;558}559560if (now - step_start_time_ms >= step_time_limit_ms) {561// we have passed the maximum stop time562step = UPDATE_GAINS;563}564}565566// twitching_test_rate - twitching tests567// update min and max and test for end conditions568void AC_AutoTune_Multi::twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min, float angle_min)569{570if (angle >= angle_max) {571if (is_equal(rate, meas_rate_min) || (angle_min > 0.95 * angle_max)) {572// we have reached the angle limit before completing the measurement of maximum and minimum573// reduce the maximum target rate574if (step_scaler > 0.2f) {575step_scaler *= 0.9f;576} else {577LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);578GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Twitch Size Determination Failed");579mode = FAILED;580LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);581}582// ignore result and start test again583step = ABORT;584} else {585step = UPDATE_GAINS;586}587}588}589590// twitching_test_angle - twitching tests591// update min and max and test for end conditions592void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angle_target_max, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max)593{594const uint32_t now = AP_HAL::millis();595596// capture maximum angle597if (angle > meas_angle_max) {598// the angle still increasing599meas_angle_max = angle;600meas_angle_min = angle;601}602603// capture minimum angle after we have reached a reasonable maximum angle604if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.25)) {605// the measurement is bouncing back606meas_angle_min = angle;607}608609// capture maximum rate610if (rate > meas_rate_max) {611// the measurement is still increasing612meas_rate_max = rate;613meas_rate_min = rate;614}615616// capture minimum rate after we have reached maximum rate617if (rate < meas_rate_min) {618// the measurement is still decreasing619meas_rate_min = rate;620}621622// calculate early stopping time based on the time it takes to get to 63.21%623if (meas_angle_max < angle_target_max * 0.6321) {624// the measurement not reached the 63.21% threshold yet625step_time_limit_ms = (now - step_start_time_ms) * 3;626step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);627}628629if (meas_angle_max > angle_target_max) {630// the measurement has passed the maximum angle631step = UPDATE_GAINS;632}633634if (meas_angle_max - meas_angle_min > meas_angle_max * aggressiveness) {635// the measurement has passed 50% of the maximum angle and bounce back is larger than the threshold636step = UPDATE_GAINS;637}638639if (now - step_start_time_ms >= step_time_limit_ms) {640// we have passed the maximum stop time641step = UPDATE_GAINS;642}643}644645// twitching_measure_acceleration - measure rate of change of measurement646void AC_AutoTune_Multi::twitching_measure_acceleration(float &accel_average, float rate, float &rate_max) const647{648if (rate_max < rate) {649rate_max = rate;650accel_average = (1000.0 * rate_max) / (AP_HAL::millis() - step_start_time_ms);651}652}653654// update gains for the rate p up tune type655void AC_AutoTune_Multi::updating_rate_p_up_all(AxisType test_axis)656{657switch (test_axis) {658case AxisType::ROLL:659updating_rate_p_up_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);660break;661case AxisType::PITCH:662updating_rate_p_up_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);663break;664case AxisType::YAW:665updating_rate_p_up_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max, false);666break;667case AxisType::YAW_D:668updating_rate_p_up_d_down(tune_yaw_rd, min_d, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);669break;670}671}672673// update gains for the rate d up tune type674void AC_AutoTune_Multi::updating_rate_d_up_all(AxisType test_axis)675{676switch (test_axis) {677case AxisType::ROLL:678updating_rate_d_up(tune_roll_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);679break;680case AxisType::PITCH:681updating_rate_d_up(tune_pitch_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);682break;683case AxisType::YAW:684updating_rate_d_up(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RLPF_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);685break;686case AxisType::YAW_D:687updating_rate_d_up(tune_yaw_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);688break;689}690}691692// update gains for the rate d down tune type693void AC_AutoTune_Multi::updating_rate_d_down_all(AxisType test_axis)694{695switch (test_axis) {696case AxisType::ROLL:697updating_rate_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);698break;699case AxisType::PITCH:700updating_rate_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);701break;702case AxisType::YAW:703updating_rate_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);704break;705case AxisType::YAW_D:706updating_rate_d_down(tune_yaw_rd, min_d, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);707break;708}709}710711// update gains for the angle p up tune type712void AC_AutoTune_Multi::updating_angle_p_up_all(AxisType test_axis)713{714switch (test_axis) {715case AxisType::ROLL:716updating_angle_p_up(tune_roll_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);717break;718case AxisType::PITCH:719updating_angle_p_up(tune_pitch_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);720break;721case AxisType::YAW:722case AxisType::YAW_D:723updating_angle_p_up(tune_yaw_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);724break;725}726}727728// update gains for the angle p down tune type729void AC_AutoTune_Multi::updating_angle_p_down_all(AxisType test_axis)730{731switch (test_axis) {732case AxisType::ROLL:733updating_angle_p_down(tune_roll_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);734break;735case AxisType::PITCH:736updating_angle_p_down(tune_pitch_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);737break;738case AxisType::YAW:739case AxisType::YAW_D:740updating_angle_p_down(tune_yaw_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);741break;742}743}744745// set gains post tune for the tune type746void AC_AutoTune_Multi::set_gains_post_tune(AxisType test_axis)747{748switch (tune_type) {749case RD_UP:750break;751case RD_DOWN:752switch (test_axis) {753case AxisType::ROLL:754tune_roll_rd = MAX(min_d, tune_roll_rd * AUTOTUNE_RD_BACKOFF);755tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RD_BACKOFF);756break;757case AxisType::PITCH:758tune_pitch_rd = MAX(min_d, tune_pitch_rd * AUTOTUNE_RD_BACKOFF);759tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RD_BACKOFF);760break;761case AxisType::YAW:762tune_yaw_rLPF = MAX(AUTOTUNE_RLPF_MIN, tune_yaw_rLPF * AUTOTUNE_RD_BACKOFF);763tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);764break;765case AxisType::YAW_D:766tune_yaw_rd = MAX(min_d, tune_yaw_rd * AUTOTUNE_RD_BACKOFF);767tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);768break;769}770break;771case RP_UP:772switch (test_axis) {773case AxisType::ROLL:774tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RP_BACKOFF);775break;776case AxisType::PITCH:777tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RP_BACKOFF);778break;779case AxisType::YAW:780case AxisType::YAW_D:781tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF);782break;783}784break;785case SP_DOWN:786break;787case SP_UP:788switch (test_axis) {789case AxisType::ROLL:790tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF);791tune_roll_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);792break;793case AxisType::PITCH:794tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF);795tune_pitch_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);796break;797case AxisType::YAW:798case AxisType::YAW_D:799tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF);800tune_yaw_accel = MAX(AUTOTUNE_Y_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_Y_BACKOFF);801break;802}803break;804case RFF_UP:805case MAX_GAINS:806case TUNE_CHECK:807// this should never happen808INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);809break;810case TUNE_COMPLETE:811break;812}813}814815// updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back816// optimize D term while keeping the maximum just below the target by adjusting P817void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)818{819if (meas_rate_max > rate_target) {820// if maximum measurement was higher than target821// reduce P gain (which should reduce maximum)822tune_p -= tune_p * tune_p_step_ratio;823if (tune_p < tune_p_min) {824// P gain is at minimum so start reducing D825tune_p = tune_p_min;826tune_d -= tune_d * tune_d_step_ratio;827if (tune_d <= tune_d_min) {828// We have reached minimum D gain so stop tuning829tune_d = tune_d_min;830counter = AUTOTUNE_SUCCESS_COUNT;831LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);832// This may be mean AGGR should be increased or MIN_D decreased833GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");834}835}836} else if ((meas_rate_max < rate_target * (1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {837// we have not achieved a high enough maximum to get a good measurement of bounce back.838// increase P gain (which should increase maximum)839tune_p += tune_p * tune_p_step_ratio;840if (tune_p >= tune_p_max) {841tune_p = tune_p_max;842LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);843}844} else {845// we have a good measurement of bounce back846if (meas_rate_max-meas_rate_min > meas_rate_max * aggressiveness) {847// ignore the next result unless it is the same as this one848ignore_next = true;849// bounce back is bigger than our threshold so increment the success counter850counter++;851} else {852if (ignore_next == false) {853// bounce back is smaller than our threshold so decrement the success counter854if (counter > 0) {855counter--;856}857// increase D gain (which should increase bounce back)858tune_d += tune_d*tune_d_step_ratio * 2.0;859// stop tuning if we hit maximum D860if (tune_d >= tune_d_max) {861tune_d = tune_d_max;862counter = AUTOTUNE_SUCCESS_COUNT;863LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);864}865} else {866ignore_next = false;867}868}869}870}871872// updating_rate_d_down - decrease D and adjust P to optimize the D term for no bounce back873// optimize D term while keeping the maximum just below the target by adjusting P874void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)875{876if (meas_rate_max > rate_target) {877// if maximum measurement was higher than target878// reduce P gain (which should reduce maximum)879tune_p -= tune_p*tune_p_step_ratio;880if (tune_p < tune_p_min) {881// P gain is at minimum so start reducing D gain882tune_p = tune_p_min;883tune_d -= tune_d*tune_d_step_ratio;884if (tune_d <= tune_d_min) {885// We have reached minimum D so stop tuning886tune_d = tune_d_min;887counter = AUTOTUNE_SUCCESS_COUNT;888LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);889// This may be mean AGGR should be increased or MIN_D decreased890GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");891}892}893} else if ((meas_rate_max < rate_target*(1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {894// we have not achieved a high enough maximum to get a good measurement of bounce back.895// increase P gain (which should increase maximum)896tune_p += tune_p * tune_p_step_ratio;897if (tune_p >= tune_p_max) {898tune_p = tune_p_max;899LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);900}901} else {902// we have a good measurement of bounce back903if (meas_rate_max - meas_rate_min < meas_rate_max * aggressiveness) {904if (ignore_next == false) {905// bounce back is less than our threshold so increment the success counter906counter++;907} else {908ignore_next = false;909}910} else {911// ignore the next result unless it is the same as this one912ignore_next = true;913// bounce back is larger than our threshold so decrement the success counter914if (counter > 0) {915counter--;916}917// decrease D gain (which should decrease bounce back)918tune_d -= tune_d * tune_d_step_ratio;919// stop tuning if we hit minimum D920if (tune_d <= tune_d_min) {921tune_d = tune_d_min;922counter = AUTOTUNE_SUCCESS_COUNT;923LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);924// This may be mean AGGR should be increased or MIN_D decreased925GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");926}927}928}929}930931// updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing932// P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold933void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max, bool fail_min_d)934{935if (meas_rate_max > rate_target * (1.0 + 0.5 * aggressiveness)) {936// ignore the next result unless it is the same as this one937ignore_next = true;938// if maximum measurement was greater than target so increment the success counter939counter++;940} else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target * (1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max - meas_rate_min > meas_rate_max * aggressiveness) && (tune_d > tune_d_min)) {941// if bounce back was larger than the threshold so decrement the success counter942if (counter > 0) {943counter--;944}945// decrease D gain (which should decrease bounce back)946tune_d -= tune_d * tune_d_step_ratio;947// do not decrease the D term past the minimum948if (tune_d <= tune_d_min) {949tune_d = tune_d_min;950LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);951if (fail_min_d) {952GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Rate D Gain Determination Failed");953mode = FAILED;954LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);955}956}957// decrease P gain to match D gain reduction958tune_p -= tune_p * tune_p_step_ratio;959// do not decrease the P term past the minimum960if (tune_p <= tune_p_min) {961tune_p = tune_p_min;962GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Rate P Gain Determination Failed");963mode = FAILED;964LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);965}966} else {967if (ignore_next == false) {968// if maximum measurement was lower than target so decrement the success counter969if (counter > 0) {970counter--;971}972// increase P gain (which should increase the maximum)973tune_p += tune_p * tune_p_step_ratio;974// stop tuning if we hit maximum P975if (tune_p >= tune_p_max) {976tune_p = tune_p_max;977counter = AUTOTUNE_SUCCESS_COUNT;978LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);979}980} else {981ignore_next = false;982}983}984}985986// updating_angle_p_down - decrease P until we don't reach the target before time out987// P is decreased to ensure we are not overshooting the target988void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)989{990if (meas_angle_max < angle_target * (1 + 0.5 * aggressiveness)) {991if (ignore_next == false) {992// if maximum measurement was lower than target so increment the success counter993counter++;994} else {995ignore_next = false;996}997} else {998// ignore the next result unless it is the same as this one999ignore_next = true;1000// if maximum measurement was higher than target so decrement the success counter1001if (counter > 0) {1002counter--;1003}1004// decrease P gain (which should decrease the maximum)1005tune_p -= tune_p*tune_p_step_ratio;1006// stop tuning if we hit maximum P1007if (tune_p <= tune_p_min) {1008tune_p = tune_p_min;1009counter = AUTOTUNE_SUCCESS_COUNT;1010LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);1011GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Angle P Gain Determination Failed");1012mode = FAILED;1013LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);1014}1015}1016}10171018// updating_angle_p_up - increase P to ensure the target is reached1019// P is increased until we achieve our target within a reasonable time1020void AC_AutoTune_Multi::updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)1021{1022if ((meas_angle_max > angle_target * (1 + 0.5 * aggressiveness)) ||1023((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max * aggressiveness))) {1024// ignore the next result unless it is the same as this one1025ignore_next = true;1026// if maximum measurement was greater than target so increment the success counter1027counter++;1028} else {1029if (ignore_next == false) {1030// if maximum measurement was lower than target so decrement the success counter1031if (counter > 0) {1032counter--;1033}1034// increase P gain (which should increase the maximum)1035tune_p += tune_p * tune_p_step_ratio;1036// stop tuning if we hit maximum P1037if (tune_p >= tune_p_max) {1038tune_p = tune_p_max;1039counter = AUTOTUNE_SUCCESS_COUNT;1040LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);1041}1042} else {1043ignore_next = false;1044}1045}1046}10471048#if HAL_LOGGING_ENABLED1049void AC_AutoTune_Multi::Log_AutoTune()1050{1051if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {1052switch (axis) {1053case AxisType::ROLL:1054Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);1055break;1056case AxisType::PITCH:1057Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);1058break;1059case AxisType::YAW:1060Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max);1061break;1062case AxisType::YAW_D:1063Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max);1064break;1065}1066} else {1067switch (axis) {1068case AxisType::ROLL:1069Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);1070break;1071case AxisType::PITCH:1072Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);1073break;1074case AxisType::YAW:1075Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max);1076break;1077case AxisType::YAW_D:1078Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max);1079break;1080}1081}10821083}10841085void AC_AutoTune_Multi::Log_AutoTuneDetails()1086{1087Log_Write_AutoTuneDetails(lean_angle, rotation_rate);1088}10891090// @LoggerMessage: ATUN1091// @Description: Copter/QuadPlane AutoTune1092// @Vehicles: Copter, Plane1093// @Field: TimeUS: Time since system startup1094// @Field: Axis: which axis is currently being tuned1095// @Field: TuneStep: step in autotune process1096// @Field: Targ: target angle or rate, depending on tuning step1097// @Field: Min: measured minimum target angle or rate1098// @Field: Max: measured maximum target angle or rate1099// @Field: RP: new rate gain P term1100// @Field: RD: new rate gain D term1101// @Field: SP: new angle P term1102// @Field: ddt: maximum measured twitching acceleration11031104// Write an Autotune data packet1105void AC_AutoTune_Multi::Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)1106{1107AP::logger().Write(1108"ATUN",1109"TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt",1110"s--ddd---o",1111"F--000---0",1112"QBBfffffff",1113AP_HAL::micros64(),1114axis,1115tune_step,1116meas_target*0.01,1117meas_min*0.01,1118meas_max*0.01,1119new_gain_rp,1120new_gain_rd,1121new_gain_sp,1122new_ddt);1123}11241125// Write an Autotune data packet1126void AC_AutoTune_Multi::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)1127{1128// @LoggerMessage: ATDE1129// @Description: AutoTune data packet1130// @Field: TimeUS: Time since system startup1131// @Field: Angle: current angle1132// @Field: Rate: current angular rate1133AP::logger().WriteStreaming(1134"ATDE",1135"TimeUS,Angle,Rate",1136"sdk",1137"F00",1138"Qff",1139AP_HAL::micros64(),1140angle_cd*0.01,1141rate_cds*0.01);1142}1143#endif // HAL_LOGGING_ENABLED11441145float AC_AutoTune_Multi::target_angle_max_rp_cd() const1146{1147return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MAX_RP_SCALE;1148}11491150float AC_AutoTune_Multi::target_angle_max_y_cd() const1151{1152// Aircraft with small lean angle will generally benefit from proportional smaller yaw twitch size1153return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MAX_Y_SCALE;1154}11551156float AC_AutoTune_Multi::target_angle_min_rp_cd() const1157{1158return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MIN_RP_SCALE;1159}11601161float AC_AutoTune_Multi::target_angle_min_y_cd() const1162{1163// Aircraft with small lean angle will generally benefit from proportional smaller yaw twitch size1164return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MIN_Y_SCALE;1165}11661167float AC_AutoTune_Multi::angle_lim_max_rp_cd() const1168{1169return attitude_control->lean_angle_max_cd() * AUTOTUNE_ANGLE_ABORT_RP_SCALE;1170}11711172float AC_AutoTune_Multi::angle_lim_neg_rpy_cd() const1173{1174return attitude_control->lean_angle_max_cd() * AUTOTUNE_ANGLE_NEG_RP_SCALE;1175}11761177void AC_AutoTune_Multi::twitch_test_init()1178{1179float target_max_rate;1180switch (axis) {1181case AxisType::ROLL:1182angle_abort = target_angle_max_rp_cd();1183target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler * AUTOTUNE_TARGET_RATE_RLLPIT_CDS);1184target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_roll()) * 100.0, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);1185target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_roll()) * 100.0, target_angle_min_rp_cd(), target_angle_max_rp_cd());1186rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_D_hz() * 2.0);1187break;11881189case AxisType::PITCH:1190angle_abort = target_angle_max_rp_cd();1191target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler * AUTOTUNE_TARGET_RATE_RLLPIT_CDS);1192target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_pitch()) * 100.0, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);1193target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_pitch()) * 100.0, target_angle_min_rp_cd(), target_angle_max_rp_cd());1194rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_D_hz() * 2.0);1195break;11961197case AxisType::YAW:1198case AxisType::YAW_D:1199angle_abort = target_angle_max_y_cd();1200target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS);1201target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw() * 0.75) * 100.0, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate);1202target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw() * 0.75) * 100.0, target_angle_min_y_cd(), target_angle_max_y_cd());1203if (axis == AxisType::YAW_D) {1204rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_yaw_pid().filt_D_hz() * 2.0);1205} else {1206rotation_rate_filt.set_cutoff_frequency(AUTOTUNE_Y_FILT_FREQ);1207}1208break;1209}12101211if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {1212// todo: consider if this should be done for other axis1213rotation_rate_filt.reset(start_rate);1214} else {1215rotation_rate_filt.reset(0.0);1216}1217twitch_first_iter = true;1218test_rate_max = 0.0;1219test_rate_min = 0.0;1220test_angle_max = 0.0;1221test_angle_min = 0.0;1222accel_measure_rate_max = 0.0;1223}12241225//run twitch test1226void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign)1227{1228// disable rate limits1229attitude_control->use_sqrt_controller(false);1230// hold current attitude12311232if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {1233// step angle targets on first iteration1234if (twitch_first_iter) {1235twitch_first_iter = false;1236// Testing increasing stabilize P gain so will set lean angle target1237switch (test_axis) {1238case AxisType::ROLL:1239// request roll to 20deg1240attitude_control->input_angle_step_bf_roll_pitch_yaw(dir_sign * target_angle, 0.0, 0.0);1241break;1242case AxisType::PITCH:1243// request pitch to 20deg1244attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0, dir_sign * target_angle, 0.0);1245break;1246case AxisType::YAW:1247case AxisType::YAW_D:1248// request yaw to 20deg1249attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0, 0.0, dir_sign * target_angle);1250break;1251}1252} else {1253attitude_control->input_rate_bf_roll_pitch_yaw(0.0, 0.0, 0.0);1254}1255} else {1256// Testing rate P and D gains so will set body-frame rate targets.1257// Rate controller will use existing body-frame rates and convert to motor outputs1258// for all axes except the one we override here.1259switch (test_axis) {1260case AxisType::ROLL:1261// override body-frame roll rate1262attitude_control->input_rate_step_bf_roll_pitch_yaw(dir_sign * target_rate + start_rate, 0.0f, 0.0f);1263break;1264case AxisType::PITCH:1265// override body-frame pitch rate1266attitude_control->input_rate_step_bf_roll_pitch_yaw(0.0f, dir_sign * target_rate + start_rate, 0.0f);1267break;1268case AxisType::YAW:1269case AxisType::YAW_D:1270// override body-frame yaw rate1271attitude_control->input_rate_step_bf_roll_pitch_yaw(0.0f, 0.0f, dir_sign * target_rate + start_rate);1272break;1273}1274}12751276// capture this iteration's rotation rate and lean angle1277float gyro_reading = 0;1278switch (test_axis) {1279case AxisType::ROLL:1280gyro_reading = ahrs_view->get_gyro().x;1281lean_angle = dir_sign * (ahrs_view->roll_sensor - (int32_t)start_angle);1282break;1283case AxisType::PITCH:1284gyro_reading = ahrs_view->get_gyro().y;1285lean_angle = dir_sign * (ahrs_view->pitch_sensor - (int32_t)start_angle);1286break;1287case AxisType::YAW:1288case AxisType::YAW_D:1289gyro_reading = ahrs_view->get_gyro().z;1290lean_angle = dir_sign * wrap_180_cd(ahrs_view->yaw_sensor-(int32_t)start_angle);1291break;1292}12931294// Add filter to measurements1295float filter_value;1296switch (tune_type) {1297case SP_DOWN:1298case SP_UP:1299filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0);1300break;1301default:1302filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0 - start_rate);1303break;1304}1305rotation_rate = rotation_rate_filt.apply(filter_value,1306AP::scheduler().get_loop_period_s());13071308switch (tune_type) {1309case RD_UP:1310case RD_DOWN:1311twitching_test_rate(lean_angle, rotation_rate, target_rate, test_rate_min, test_rate_max, test_angle_min);1312twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max);1313twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);1314break;1315case RP_UP:1316twitching_test_rate(lean_angle, rotation_rate, target_rate * (1 + 0.5 * aggressiveness), test_rate_min, test_rate_max, test_angle_min);1317twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max);1318twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);1319break;1320case SP_DOWN:1321case SP_UP:1322twitching_test_angle(lean_angle, rotation_rate, target_angle * (1 + 0.5 * aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max);1323twitching_measure_acceleration(test_accel_max, rotation_rate - dir_sign * start_rate, accel_measure_rate_max);1324break;1325case RFF_UP:1326case MAX_GAINS:1327case TUNE_CHECK:1328// this should never happen1329INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1330break;1331default:1332break;1333}1334}13351336// get_testing_step_timeout_ms accessor1337uint32_t AC_AutoTune_Multi::get_testing_step_timeout_ms() const1338{1339return AUTOTUNE_TESTING_STEP_TIMEOUT_MS;1340}134113421343#endif // AC_AUTOTUNE_ENABLED134413451346