123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728 |
- #include "AC_AutoTune.h"
- #include <GCS_MAVLink/GCS.h>
- #include <AP_Scheduler/AP_Scheduler.h>
- #define AUTOTUNE_AXIS_BITMASK_ROLL 1
- #define AUTOTUNE_AXIS_BITMASK_PITCH 2
- #define AUTOTUNE_AXIS_BITMASK_YAW 4
- #define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500
- #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U
- #define AUTOTUNE_LEVEL_ANGLE_CD 500
- #define AUTOTUNE_LEVEL_RATE_RP_CD 1000
- #define AUTOTUNE_LEVEL_RATE_Y_CD 750
- #define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 500
- #define AUTOTUNE_LEVEL_TIMEOUT_MS 2000
- #define AUTOTUNE_RD_STEP 0.05f
- #define AUTOTUNE_RP_STEP 0.05f
- #define AUTOTUNE_SP_STEP 0.05f
- #define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f
- #define AUTOTUNE_PI_RATIO_FINAL 1.0f
- #define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1f
- #define AUTOTUNE_RD_MAX 0.200f
- #define AUTOTUNE_RLPF_MIN 1.0f
- #define AUTOTUNE_RLPF_MAX 5.0f
- #define AUTOTUNE_RP_MIN 0.01f
- #define AUTOTUNE_RP_MAX 2.0f
- #define AUTOTUNE_SP_MAX 20.0f
- #define AUTOTUNE_SP_MIN 0.5f
- #define AUTOTUNE_RP_ACCEL_MIN 4000.0f
- #define AUTOTUNE_Y_ACCEL_MIN 1000.0f
- #define AUTOTUNE_Y_FILT_FREQ 10.0f
- #define AUTOTUNE_SUCCESS_COUNT 4
- #define AUTOTUNE_D_UP_DOWN_MARGIN 0.2f
- #define AUTOTUNE_RD_BACKOFF 1.0f
- #define AUTOTUNE_RP_BACKOFF 1.0f
- #define AUTOTUNE_SP_BACKOFF 0.9f
- #define AUTOTUNE_ACCEL_RP_BACKOFF 1.0f
- #define AUTOTUNE_ACCEL_Y_BACKOFF 1.0f
- #define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD 2000
- #define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000
- #define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000
- #define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500
- #define AUTOTUNE_TARGET_ANGLE_YAW_CD 3000
- #define AUTOTUNE_TARGET_RATE_YAW_CDS 9000
- #define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD 500
- #define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500
- #define AUTOTUNE_MESSAGE_STARTED 0
- #define AUTOTUNE_MESSAGE_STOPPED 1
- #define AUTOTUNE_MESSAGE_SUCCESS 2
- #define AUTOTUNE_MESSAGE_FAILED 3
- #define AUTOTUNE_MESSAGE_SAVED_GAINS 4
- #define AUTOTUNE_ANNOUNCE_INTERVAL_MS 2000
- const AP_Param::GroupInfo AC_AutoTune::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO("AXES", 1, AC_AutoTune, axis_bitmask, 7),
-
-
-
-
-
- AP_GROUPINFO("AGGR", 2, AC_AutoTune, aggressiveness, 0.1f),
-
-
-
-
-
- AP_GROUPINFO("MIN_D", 3, AC_AutoTune, min_d, 0.001f),
- AP_GROUPEND
- };
- AC_AutoTune::AC_AutoTune()
- {
- AP_Param::setup_object_defaults(this, var_info);
- }
- bool AC_AutoTune::init_internals(bool _use_poshold,
- AC_AttitudeControl_Multi *_attitude_control,
- AC_PosControl *_pos_control,
- AP_AHRS_View *_ahrs_view,
- AP_InertialNav *_inertial_nav)
- {
- bool success = true;
- use_poshold = _use_poshold;
- attitude_control = _attitude_control;
- pos_control = _pos_control;
- ahrs_view = _ahrs_view;
- inertial_nav = _inertial_nav;
- motors = AP_Motors::get_singleton();
- switch (mode) {
- case FAILED:
-
- mode = UNINITIALISED;
-
- FALLTHROUGH;
- case UNINITIALISED:
-
- success = start();
- if (success) {
-
- backup_gains_and_initialise();
-
- mode = TUNING;
-
- update_gcs(AUTOTUNE_MESSAGE_STARTED);
- }
- break;
- case TUNING:
-
- success = start();
- if (success) {
-
- load_gains(GAIN_INTRA_TEST);
- Log_Write_Event(EVENT_AUTOTUNE_RESTART);
- update_gcs(AUTOTUNE_MESSAGE_STARTED);
- }
- break;
- case SUCCESS:
-
-
- load_gains(GAIN_TUNED);
- Log_Write_Event(EVENT_AUTOTUNE_PILOT_TESTING);
- break;
- }
- have_position = false;
- return success;
- }
- void AC_AutoTune::stop()
- {
-
- load_gains(GAIN_ORIGINAL);
-
- attitude_control->use_sqrt_controller(true);
- update_gcs(AUTOTUNE_MESSAGE_STOPPED);
- Log_Write_Event(EVENT_AUTOTUNE_OFF);
-
-
- }
- bool AC_AutoTune::start(void)
- {
- if (!motors->armed()) {
- return false;
- }
-
- init_z_limits();
-
- if (!pos_control->is_active_z()) {
- pos_control->set_alt_target_to_current_alt();
- pos_control->set_desired_velocity_z(inertial_nav->get_velocity_z());
- }
- return true;
- }
- const char *AC_AutoTune::level_issue_string() const
- {
- switch (level_problem.issue) {
- case LevelIssue::NONE:
- return "None";
- case LevelIssue::ANGLE_ROLL:
- return "Angle(R)";
- case LevelIssue::ANGLE_PITCH:
- return "Angle(P)";
- case LevelIssue::ANGLE_YAW:
- return "Angle(Y)";
- case LevelIssue::RATE_ROLL:
- return "Rate(R)";
- case LevelIssue::RATE_PITCH:
- return "Rate(P)";
- case LevelIssue::RATE_YAW:
- return "Rate(Y)";
- }
- return "Bug";
- }
- void AC_AutoTune::send_step_string()
- {
- if (pilot_override) {
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
- return;
- }
- switch (step) {
- case WAITING_FOR_LEVEL:
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: WFL (%s) (%f > %f)", level_issue_string(), (double)(level_problem.current*0.01f), (double)(level_problem.maximum*0.01f));
- return;
- case UPDATE_GAINS:
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: UPDATING_GAINS");
- return;
- case TWITCHING:
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: TWITCHING");
- return;
- }
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: unknown step");
- }
- const char *AC_AutoTune::type_string() const
- {
- switch (tune_type) {
- case RD_UP:
- return "Rate D Up";
- case RD_DOWN:
- return "Rate D Down";
- case RP_UP:
- return "Rate P Up";
- case SP_DOWN:
- return "Angle P Down";
- case SP_UP:
- return "Angle P Up";
- }
- return "Bug";
- }
- void AC_AutoTune::do_gcs_announcements()
- {
- const uint32_t now = AP_HAL::millis();
- if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) {
- return;
- }
- float tune_rp = 0.0f;
- float tune_rd = 0.0f;
- float tune_sp = 0.0f;
- float tune_accel = 0.0f;
- char axis_char = '?';
- switch (axis) {
- case ROLL:
- tune_rp = tune_roll_rp;
- tune_rd = tune_roll_rd;
- tune_sp = tune_roll_sp;
- tune_accel = tune_roll_accel;
- axis_char = 'R';
- break;
- case PITCH:
- tune_rp = tune_pitch_rp;
- tune_rd = tune_pitch_rd;
- tune_sp = tune_pitch_sp;
- tune_accel = tune_pitch_accel;
- axis_char = 'P';
- break;
- case YAW:
- tune_rp = tune_yaw_rp;
- tune_rd = tune_yaw_rLPF;
- tune_sp = tune_yaw_sp;
- tune_accel = tune_yaw_accel;
- axis_char = 'Y';
- break;
- }
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: (%c) %s", axis_char, type_string());
- send_step_string();
- if (!is_zero(lean_angle)) {
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: lean=%f target=%f", (double)lean_angle, (double)target_angle);
- }
- if (!is_zero(rotation_rate)) {
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rotation=%f target=%f", (double)(rotation_rate*0.01f), (double)(target_rate*0.01f));
- }
- switch (tune_type) {
- case RD_UP:
- case RD_DOWN:
- case RP_UP:
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f d=%f", (double)tune_rp, (double)tune_rd);
- break;
- case SP_DOWN:
- case SP_UP:
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f accel=%f", (double)tune_sp, (double)tune_accel);
- break;
- }
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: success %u/%u", counter, AUTOTUNE_SUCCESS_COUNT);
- announce_time = now;
- }
- void AC_AutoTune::run()
- {
-
- init_z_limits();
-
-
- if (!motors->armed() || !motors->get_interlock()) {
- motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
- attitude_control->set_throttle_out(0.0f, true, 0.0f);
- pos_control->relax_alt_hold_controllers(0.0f);
- return;
- }
- float target_roll_cd, target_pitch_cd, target_yaw_rate_cds;
- get_pilot_desired_rp_yrate_cd(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
-
- const float target_climb_rate_cms = get_pilot_desired_climb_rate_cms();
- const bool zero_rp_input = is_zero(target_roll_cd) && is_zero(target_pitch_cd);
- const uint32_t now = AP_HAL::millis();
- if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) {
- if (!pilot_override) {
- pilot_override = true;
-
- load_gains(GAIN_ORIGINAL);
- attitude_control->use_sqrt_controller(true);
- }
-
- override_time = now;
- if (!zero_rp_input) {
-
- have_position = false;
- }
- } else if (pilot_override) {
-
- if (now - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) {
- pilot_override = false;
-
-
- step = WAITING_FOR_LEVEL;
- step_start_time_ms = now;
- level_start_time_ms = now;
- desired_yaw_cd = ahrs_view->yaw_sensor;
- }
- }
- if (pilot_override) {
- if (now - last_pilot_override_warning > 1000) {
- gcs().send_text(MAV_SEVERITY_INFO, "AUTOTUNE: pilot overrides active");
- last_pilot_override_warning = now;
- }
- }
- if (zero_rp_input) {
-
- get_poshold_attitude(target_roll_cd, target_pitch_cd, desired_yaw_cd);
- }
-
- motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
-
- if (pilot_override || mode != TUNING) {
- attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
- } else {
-
- control_attitude();
-
- do_gcs_announcements();
- }
-
- pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate_cms, AP::scheduler().get_last_loop_time_s(), false);
- pos_control->update_z_controller();
- }
- bool AC_AutoTune::check_level(const LevelIssue issue, const float current, const float maximum)
- {
- if (current > maximum) {
- level_problem.current = current;
- level_problem.maximum = maximum;
- level_problem.issue = issue;
- return false;
- }
- return true;
- }
- bool AC_AutoTune::currently_level()
- {
- float threshold_mul = 1.0;
- if (AP_HAL::millis() - level_start_time_ms > AUTOTUNE_LEVEL_TIMEOUT_MS) {
-
-
- threshold_mul *= 2;
- }
- if (!check_level(LevelIssue::ANGLE_ROLL,
- abs(ahrs_view->roll_sensor - roll_cd),
- threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
- return false;
- }
- if (!check_level(LevelIssue::ANGLE_PITCH,
- abs(ahrs_view->pitch_sensor - pitch_cd),
- threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
- return false;
- }
- if (!check_level(LevelIssue::ANGLE_YAW,
- fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)),
- threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
- return false;
- }
- if (!check_level(LevelIssue::RATE_ROLL,
- (ToDeg(ahrs_view->get_gyro().x) * 100.0f),
- threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD)) {
- return false;
- }
- if (!check_level(LevelIssue::RATE_PITCH,
- (ToDeg(ahrs_view->get_gyro().y) * 100.0f),
- threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD)) {
- return false;
- }
- if (!check_level(LevelIssue::RATE_YAW,
- (ToDeg(ahrs_view->get_gyro().z) * 100.0f),
- threshold_mul*AUTOTUNE_LEVEL_RATE_Y_CD)) {
- return false;
- }
- return true;
- }
- void AC_AutoTune::control_attitude()
- {
- rotation_rate = 0.0f;
- lean_angle = 0.0f;
- const float direction_sign = positive_direction ? 1.0f : -1.0f;
- const uint32_t now = AP_HAL::millis();
-
- switch (step) {
- case WAITING_FOR_LEVEL: {
-
-
- attitude_control->use_sqrt_controller(true);
- get_poshold_attitude(roll_cd, pitch_cd, desired_yaw_cd);
-
- attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true);
-
-
- if (!currently_level()) {
- step_start_time_ms = now;
- }
-
- if (now - step_start_time_ms > AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {
- gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Twitch");
-
- step = TWITCHING;
- step_start_time_ms = now;
- step_time_limit_ms = AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
- twitch_first_iter = true;
- test_rate_max = 0.0f;
- test_rate_min = 0.0f;
- test_angle_max = 0.0f;
- test_angle_min = 0.0f;
- rotation_rate_filt.reset(0.0f);
- rate_max = 0.0f;
-
- load_gains(GAIN_TWITCH);
- } else {
-
- load_gains(GAIN_INTRA_TEST);
- }
- float target_max_rate;
- switch (axis) {
- case ROLL:
- target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_RLLPIT_CDS);
- target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_roll())*100.0f, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);
- target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_roll())*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD, AUTOTUNE_TARGET_ANGLE_RLLPIT_CD);
- abort_angle = AUTOTUNE_TARGET_ANGLE_RLLPIT_CD;
- start_rate = ToDeg(ahrs_view->get_gyro().x) * 100.0f;
- start_angle = ahrs_view->roll_sensor;
- rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_D_hz()*2.0f);
- break;
- case PITCH:
- target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_RLLPIT_CDS);
- target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_pitch())*100.0f, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);
- target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_pitch())*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD, AUTOTUNE_TARGET_ANGLE_RLLPIT_CD);
- abort_angle = AUTOTUNE_TARGET_ANGLE_RLLPIT_CD;
- start_rate = ToDeg(ahrs_view->get_gyro().y) * 100.0f;
- start_angle = ahrs_view->pitch_sensor;
- rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_D_hz()*2.0f);
- break;
- case YAW:
- target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS);
- target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate);
- target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD, AUTOTUNE_TARGET_ANGLE_YAW_CD);
- abort_angle = AUTOTUNE_TARGET_ANGLE_YAW_CD;
- start_rate = ToDeg(ahrs_view->get_gyro().z) * 100.0f;
- start_angle = ahrs_view->yaw_sensor;
- rotation_rate_filt.set_cutoff_frequency(AUTOTUNE_Y_FILT_FREQ);
- break;
- }
- if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
- rotation_rate_filt.reset(start_rate);
- } else {
- rotation_rate_filt.reset(0);
- }
- break;
- }
- case TWITCHING: {
-
- load_gains(GAIN_TWITCH);
-
- attitude_control->use_sqrt_controller(false);
-
- attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f);
- if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
-
- if (twitch_first_iter) {
- twitch_first_iter = false;
-
- switch (axis) {
- case ROLL:
-
- attitude_control->input_angle_step_bf_roll_pitch_yaw(direction_sign * target_angle, 0.0f, 0.0f);
- break;
- case PITCH:
-
- attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, direction_sign * target_angle, 0.0f);
- break;
- case YAW:
-
- attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, 0.0f, direction_sign * target_angle);
- break;
- }
- }
- } else {
-
-
-
- switch (axis) {
- case ROLL:
-
- attitude_control->rate_bf_roll_target(direction_sign * target_rate + start_rate);
- break;
- case PITCH:
-
- attitude_control->rate_bf_pitch_target(direction_sign * target_rate + start_rate);
- break;
- case YAW:
-
- attitude_control->rate_bf_yaw_target(direction_sign * target_rate + start_rate);
- break;
- }
- }
-
- float gyro_reading = 0;
- switch (axis) {
- case ROLL:
- gyro_reading = ahrs_view->get_gyro().x;
- lean_angle = direction_sign * (ahrs_view->roll_sensor - (int32_t)start_angle);
- break;
- case PITCH:
- gyro_reading = ahrs_view->get_gyro().y;
- lean_angle = direction_sign * (ahrs_view->pitch_sensor - (int32_t)start_angle);
- break;
- case YAW:
- gyro_reading = ahrs_view->get_gyro().z;
- lean_angle = direction_sign * wrap_180_cd(ahrs_view->yaw_sensor-(int32_t)start_angle);
- break;
- }
-
- float filter_value;
- switch (tune_type) {
- case SP_DOWN:
- case SP_UP:
- filter_value = direction_sign * (ToDeg(gyro_reading) * 100.0f);
- break;
- default:
- filter_value = direction_sign * (ToDeg(gyro_reading) * 100.0f - start_rate);
- break;
- }
- rotation_rate = rotation_rate_filt.apply(filter_value,
- AP::scheduler().get_loop_period_s());
- switch (tune_type) {
- case RD_UP:
- case RD_DOWN:
- twitching_test_rate(rotation_rate, target_rate, test_rate_min, test_rate_max);
- twitching_measure_acceleration(test_accel_max, rotation_rate, rate_max);
- twitching_abort_rate(lean_angle, rotation_rate, abort_angle, test_rate_min);
- if (lean_angle >= target_angle) {
- step = UPDATE_GAINS;
- }
- break;
- case RP_UP:
- twitching_test_rate(rotation_rate, target_rate*(1+0.5f*aggressiveness), test_rate_min, test_rate_max);
- twitching_measure_acceleration(test_accel_max, rotation_rate, rate_max);
- twitching_abort_rate(lean_angle, rotation_rate, abort_angle, test_rate_min);
- break;
- case SP_DOWN:
- case SP_UP:
- twitching_test_angle(lean_angle, rotation_rate, target_angle*(1+0.5f*aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max);
- twitching_measure_acceleration(test_accel_max, rotation_rate - direction_sign * start_rate, rate_max);
- break;
- }
-
- Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
- AP::logger().Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
- log_pids();
- break;
- }
- case UPDATE_GAINS:
-
- attitude_control->use_sqrt_controller(true);
-
- if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
- switch (axis) {
- case ROLL:
- Log_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);
- break;
- case PITCH:
- Log_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);
- break;
- case YAW:
- Log_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);
- break;
- }
- } else {
- switch (axis) {
- case ROLL:
- Log_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);
- break;
- case PITCH:
- Log_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);
- break;
- case YAW:
- Log_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);
- break;
- }
- }
-
- switch (tune_type) {
- case RD_UP:
- switch (axis) {
- case ROLL:
- updating_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);
- break;
- case PITCH:
- updating_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);
- break;
- case YAW:
- updating_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);
- break;
- }
- break;
-
- case RD_DOWN:
- switch (axis) {
- case ROLL:
- updating_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);
- break;
- case PITCH:
- updating_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);
- break;
- case YAW:
- updating_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);
- break;
- }
- break;
-
- case RP_UP:
- switch (axis) {
- case ROLL:
- updating_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);
- break;
- case PITCH:
- updating_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);
- break;
- case YAW:
- updating_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);
- break;
- }
- break;
-
- case SP_DOWN:
- switch (axis) {
- case ROLL:
- updating_angle_p_down(tune_roll_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
- break;
- case PITCH:
- updating_angle_p_down(tune_pitch_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
- break;
- case YAW:
- updating_angle_p_down(tune_yaw_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
- break;
- }
- break;
-
- case SP_UP:
- switch (axis) {
- case ROLL:
- updating_angle_p_up(tune_roll_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
- break;
- case PITCH:
- updating_angle_p_up(tune_pitch_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
- break;
- case YAW:
- updating_angle_p_up(tune_yaw_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
- break;
- }
- break;
- }
-
- if (counter >= AUTOTUNE_SUCCESS_COUNT) {
-
- counter = 0;
-
- step_scaler = 1;
-
- switch (tune_type) {
- case RD_UP:
- tune_type = TuneType(tune_type + 1);
- break;
- case RD_DOWN:
- tune_type = TuneType(tune_type + 1);
- switch (axis) {
- case ROLL:
- tune_roll_rd = MAX(min_d, tune_roll_rd * AUTOTUNE_RD_BACKOFF);
- tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RD_BACKOFF);
- break;
- case PITCH:
- tune_pitch_rd = MAX(min_d, tune_pitch_rd * AUTOTUNE_RD_BACKOFF);
- tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RD_BACKOFF);
- break;
- case YAW:
- tune_yaw_rLPF = MAX(AUTOTUNE_RLPF_MIN, tune_yaw_rLPF * AUTOTUNE_RD_BACKOFF);
- tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);
- break;
- }
- break;
- case RP_UP:
- tune_type = TuneType(tune_type + 1);
- switch (axis) {
- case ROLL:
- tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RP_BACKOFF);
- break;
- case PITCH:
- tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RP_BACKOFF);
- break;
- case YAW:
- tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF);
- break;
- }
- break;
- case SP_DOWN:
- tune_type = TuneType(tune_type + 1);
- break;
- case SP_UP:
-
- tune_type = RD_UP;
-
- bool complete = false;
- switch (axis) {
- case ROLL:
- axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL;
- tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF);
- tune_roll_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
- if (pitch_enabled()) {
- axis = PITCH;
- } else if (yaw_enabled()) {
- axis = YAW;
- } else {
- complete = true;
- }
- break;
- case PITCH:
- axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH;
- tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF);
- tune_pitch_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
- if (yaw_enabled()) {
- axis = YAW;
- } else {
- complete = true;
- }
- break;
- case YAW:
- axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW;
- tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF);
- tune_yaw_accel = MAX(AUTOTUNE_Y_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_Y_BACKOFF);
- complete = true;
- break;
- }
-
-
- if (complete) {
- mode = SUCCESS;
- update_gcs(AUTOTUNE_MESSAGE_SUCCESS);
- Log_Write_Event(EVENT_AUTOTUNE_SUCCESS);
- AP_Notify::events.autotune_complete = true;
- } else {
- AP_Notify::events.autotune_next_axis = true;
- }
- break;
- }
- }
-
- positive_direction = !positive_direction;
- if (axis == YAW) {
- attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs_view->yaw_sensor, false);
- }
-
- load_gains(GAIN_INTRA_TEST);
-
- step = WAITING_FOR_LEVEL;
- step_start_time_ms = now;
- level_start_time_ms = step_start_time_ms;
- step_time_limit_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS;
- break;
- }
- }
- void AC_AutoTune::backup_gains_and_initialise()
- {
-
- if (roll_enabled()) {
- axis = ROLL;
- } else if (pitch_enabled()) {
- axis = PITCH;
- } else if (yaw_enabled()) {
- axis = YAW;
- }
-
- axes_completed = 0;
- current_gain_type = GAIN_ORIGINAL;
- positive_direction = false;
- step = WAITING_FOR_LEVEL;
- step_start_time_ms = AP_HAL::millis();
- level_start_time_ms = step_start_time_ms;
- tune_type = RD_UP;
- step_scaler = 1;
- desired_yaw_cd = ahrs_view->yaw_sensor;
- aggressiveness = constrain_float(aggressiveness, 0.05f, 0.2f);
- orig_bf_feedforward = attitude_control->get_bf_feedforward();
-
- orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
- orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
- orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
- orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
- orig_roll_sp = attitude_control->get_angle_roll_p().kP();
- orig_roll_accel = attitude_control->get_accel_roll_max();
- tune_roll_rp = attitude_control->get_rate_roll_pid().kP();
- tune_roll_rd = attitude_control->get_rate_roll_pid().kD();
- tune_roll_sp = attitude_control->get_angle_roll_p().kP();
- tune_roll_accel = attitude_control->get_accel_roll_max();
- orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
- orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
- orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
- orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
- orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
- orig_pitch_accel = attitude_control->get_accel_pitch_max();
- tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
- tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
- tune_pitch_sp = attitude_control->get_angle_pitch_p().kP();
- tune_pitch_accel = attitude_control->get_accel_pitch_max();
- orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
- orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
- orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
- orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
- orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
- orig_yaw_accel = attitude_control->get_accel_yaw_max();
- orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
- tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
- tune_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
- tune_yaw_sp = attitude_control->get_angle_yaw_p().kP();
- tune_yaw_accel = attitude_control->get_accel_yaw_max();
- Log_Write_Event(EVENT_AUTOTUNE_INITIALISED);
- }
- void AC_AutoTune::load_orig_gains()
- {
- attitude_control->bf_feedforward(orig_bf_feedforward);
- if (roll_enabled()) {
- if (!is_zero(orig_roll_rp)) {
- attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
- attitude_control->get_rate_roll_pid().kI(orig_roll_ri);
- attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
- attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
- attitude_control->get_angle_roll_p().kP(orig_roll_sp);
- attitude_control->set_accel_roll_max(orig_roll_accel);
- }
- }
- if (pitch_enabled()) {
- if (!is_zero(orig_pitch_rp)) {
- attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
- attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri);
- attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
- attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
- attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
- attitude_control->set_accel_pitch_max(orig_pitch_accel);
- }
- }
- if (yaw_enabled()) {
- if (!is_zero(orig_yaw_rp)) {
- attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
- attitude_control->get_rate_yaw_pid().kI(orig_yaw_ri);
- attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
- attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
- attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF);
- attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
- attitude_control->set_accel_yaw_max(orig_yaw_accel);
- }
- }
- }
- void AC_AutoTune::load_tuned_gains()
- {
- if (!attitude_control->get_bf_feedforward()) {
- attitude_control->bf_feedforward(true);
- attitude_control->set_accel_roll_max(0.0f);
- attitude_control->set_accel_pitch_max(0.0f);
- }
- if (roll_enabled()) {
- if (!is_zero(tune_roll_rp)) {
- attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
- attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
- attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
- attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
- attitude_control->get_angle_roll_p().kP(tune_roll_sp);
- attitude_control->set_accel_roll_max(tune_roll_accel);
- }
- }
- if (pitch_enabled()) {
- if (!is_zero(tune_pitch_rp)) {
- attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
- attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
- attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
- attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
- attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
- attitude_control->set_accel_pitch_max(tune_pitch_accel);
- }
- }
- if (yaw_enabled()) {
- if (!is_zero(tune_yaw_rp)) {
- attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
- attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
- attitude_control->get_rate_yaw_pid().kD(0.0f);
- attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
- attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
- attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
- attitude_control->set_accel_yaw_max(tune_yaw_accel);
- }
- }
- }
- void AC_AutoTune::load_intra_test_gains()
- {
-
-
- attitude_control->bf_feedforward(true);
- if (roll_enabled()) {
- attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
- attitude_control->get_rate_roll_pid().kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
- attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
- attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
- attitude_control->get_angle_roll_p().kP(orig_roll_sp);
- }
- if (pitch_enabled()) {
- attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
- attitude_control->get_rate_pitch_pid().kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
- attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
- attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
- attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
- }
- if (yaw_enabled()) {
- attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
- attitude_control->get_rate_yaw_pid().kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
- attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
- attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
- attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF);
- attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
- }
- }
- void AC_AutoTune::load_twitch_gains()
- {
- switch (axis) {
- case ROLL:
- attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
- attitude_control->get_rate_roll_pid().kI(tune_roll_rp*0.01f);
- attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
- attitude_control->get_rate_roll_pid().ff(0.0f);
- attitude_control->get_angle_roll_p().kP(tune_roll_sp);
- break;
- case PITCH:
- attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
- attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*0.01f);
- attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
- attitude_control->get_rate_pitch_pid().ff(0.0f);
- attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
- break;
- case YAW:
- attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
- attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f);
- attitude_control->get_rate_yaw_pid().kD(0.0f);
- attitude_control->get_rate_yaw_pid().ff(0.0f);
- attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
- attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
- break;
- }
- }
- void AC_AutoTune::load_gains(enum GainType gain_type)
- {
- if (current_gain_type == gain_type) {
- return;
- }
- switch (gain_type) {
- case GAIN_ORIGINAL:
- load_orig_gains();
- break;
- case GAIN_INTRA_TEST:
- load_intra_test_gains();
- break;
- case GAIN_TWITCH:
- load_twitch_gains();
- break;
- case GAIN_TUNED:
- load_tuned_gains();
- break;
- }
- }
- void AC_AutoTune::save_tuning_gains()
- {
-
- if (axes_completed == 0) {
- return;
- }
- if (!attitude_control->get_bf_feedforward()) {
- attitude_control->bf_feedforward_save(true);
- attitude_control->save_accel_roll_max(0.0f);
- attitude_control->save_accel_pitch_max(0.0f);
- }
-
- if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {
-
- attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
- attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
- attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
- attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
- attitude_control->get_rate_roll_pid().save_gains();
-
- attitude_control->get_angle_roll_p().kP(tune_roll_sp);
- attitude_control->get_angle_roll_p().save_gains();
-
- attitude_control->save_accel_roll_max(tune_roll_accel);
-
- orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
- orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
- orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
- orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
- orig_roll_sp = attitude_control->get_angle_roll_p().kP();
- orig_roll_accel = attitude_control->get_accel_roll_max();
- }
- if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {
-
- attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
- attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
- attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
- attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
- attitude_control->get_rate_pitch_pid().save_gains();
-
- attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
- attitude_control->get_angle_pitch_p().save_gains();
-
- attitude_control->save_accel_pitch_max(tune_pitch_accel);
-
- orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
- orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
- orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
- orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
- orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
- orig_pitch_accel = attitude_control->get_accel_pitch_max();
- }
- if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) {
-
- attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
- attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
- attitude_control->get_rate_yaw_pid().kD(0.0f);
- attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
- attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
- attitude_control->get_rate_yaw_pid().save_gains();
-
- attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
- attitude_control->get_angle_yaw_p().save_gains();
-
- attitude_control->save_accel_yaw_max(tune_yaw_accel);
-
- orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
- orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
- orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
- orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
- orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
- orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
- orig_yaw_accel = attitude_control->get_accel_pitch_max();
- }
-
- update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
- Log_Write_Event(EVENT_AUTOTUNE_SAVEDGAINS);
- reset();
- }
- void AC_AutoTune::update_gcs(uint8_t message_id)
- {
- switch (message_id) {
- case AUTOTUNE_MESSAGE_STARTED:
- gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Started");
- break;
- case AUTOTUNE_MESSAGE_STOPPED:
- gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Stopped");
- break;
- case AUTOTUNE_MESSAGE_SUCCESS:
- gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Success");
- break;
- case AUTOTUNE_MESSAGE_FAILED:
- gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Failed");
- break;
- case AUTOTUNE_MESSAGE_SAVED_GAINS:
- gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Saved gains for %s%s%s",
- (axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"",
- (axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"",
- (axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw":"");
- break;
- }
- }
- inline bool AC_AutoTune::roll_enabled()
- {
- return axis_bitmask & AUTOTUNE_AXIS_BITMASK_ROLL;
- }
- inline bool AC_AutoTune::pitch_enabled()
- {
- return axis_bitmask & AUTOTUNE_AXIS_BITMASK_PITCH;
- }
- inline bool AC_AutoTune::yaw_enabled()
- {
- return axis_bitmask & AUTOTUNE_AXIS_BITMASK_YAW;
- }
- void AC_AutoTune::twitching_test_rate(float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max)
- {
- const uint32_t now = AP_HAL::millis();
-
- if (rate > meas_rate_max) {
-
- meas_rate_max = rate;
- meas_rate_min = rate;
- }
-
- if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.5f)) {
-
- meas_rate_min = rate;
- }
-
- if (meas_rate_max < rate_target_max * 0.75f) {
-
- step_time_limit_ms = (now - step_start_time_ms) * 3;
- step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
- }
- if (meas_rate_max > rate_target_max) {
-
- step = UPDATE_GAINS;
- }
- if (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) {
-
- step = UPDATE_GAINS;
- }
- if (now - step_start_time_ms >= step_time_limit_ms) {
-
- step = UPDATE_GAINS;
- }
- }
- void AC_AutoTune::twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min)
- {
- if (angle >= angle_max) {
- if (is_equal(rate, meas_rate_min) && step_scaler > 0.5) {
-
-
- step_scaler *= 0.9f;
-
- step = WAITING_FOR_LEVEL;
- } else {
- step = UPDATE_GAINS;
- }
- }
- }
- void AC_AutoTune::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)
- {
- const uint32_t now = AP_HAL::millis();
-
- if (angle > meas_angle_max) {
-
- meas_angle_max = angle;
- meas_angle_min = angle;
- }
-
- if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.5f)) {
-
- meas_angle_min = angle;
- }
-
- if (rate > meas_rate_max) {
-
- meas_rate_max = rate;
- meas_rate_min = rate;
- }
-
- if (rate < meas_rate_min) {
-
- meas_rate_min = rate;
- }
-
- if (meas_angle_max < angle_target_max * 0.75f) {
-
- step_time_limit_ms = (now - step_start_time_ms) * 3;
- step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
- }
- if (meas_angle_max > angle_target_max) {
-
- step = UPDATE_GAINS;
- }
- if (meas_angle_max-meas_angle_min > meas_angle_max*aggressiveness) {
-
- step = UPDATE_GAINS;
- }
- if (now - step_start_time_ms >= step_time_limit_ms) {
-
- step = UPDATE_GAINS;
- }
- }
- void AC_AutoTune::twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max)
- {
- if (rate_measurement_max < rate_measurement) {
- rate_measurement_max = rate_measurement;
- rate_of_change = (1000.0f*rate_measurement_max)/(AP_HAL::millis() - step_start_time_ms);
- }
- }
- void AC_AutoTune::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)
- {
- if (meas_rate_max > rate_target) {
-
-
- tune_p -= tune_p*tune_p_step_ratio;
- if (tune_p < tune_p_min) {
-
- tune_p = tune_p_min;
- tune_d -= tune_d*tune_d_step_ratio;
- if (tune_d <= tune_d_min) {
-
- tune_d = tune_d_min;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- }
- } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
-
-
- tune_p += tune_p*tune_p_step_ratio;
- if (tune_p >= tune_p_max) {
- tune_p = tune_p_max;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- } else {
-
- if (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) {
-
- ignore_next = true;
-
- counter++;
- } else {
- if (ignore_next == false) {
-
- if (counter > 0) {
- counter--;
- }
-
- tune_d += tune_d*tune_d_step_ratio*2.0f;
-
- if (tune_d >= tune_d_max) {
- tune_d = tune_d_max;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- } else {
- ignore_next = false;
- }
- }
- }
- }
- void AC_AutoTune::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)
- {
- if (meas_rate_max > rate_target) {
-
-
- tune_p -= tune_p*tune_p_step_ratio;
- if (tune_p < tune_p_min) {
-
- tune_p = tune_p_min;
- tune_d -= tune_d*tune_d_step_ratio;
- if (tune_d <= tune_d_min) {
-
- tune_d = tune_d_min;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- }
- } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
-
-
- tune_p += tune_p*tune_p_step_ratio;
- if (tune_p >= tune_p_max) {
- tune_p = tune_p_max;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- } else {
-
- if (meas_rate_max-meas_rate_min < meas_rate_max*aggressiveness) {
- if (ignore_next == false) {
-
- counter++;
- } else {
- ignore_next = false;
- }
- } else {
-
- ignore_next = true;
-
- if (counter > 0) {
- counter--;
- }
-
- tune_d -= tune_d*tune_d_step_ratio;
-
- if (tune_d <= tune_d_min) {
- tune_d = tune_d_min;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- }
- }
- }
- void AC_AutoTune::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)
- {
- if (meas_rate_max > rate_target*(1+0.5f*aggressiveness)) {
-
- ignore_next = true;
-
- counter++;
- } else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) && (tune_d > tune_d_min)) {
-
- if (counter > 0) {
- counter--;
- }
-
- tune_d -= tune_d*tune_d_step_ratio;
-
- if (tune_d <= tune_d_min) {
- tune_d = tune_d_min;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
-
- tune_p -= tune_p*tune_p_step_ratio;
-
- if (tune_p <= tune_p_min) {
- tune_p = tune_p_min;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
-
- positive_direction = !positive_direction;
- } else {
- if (ignore_next == false) {
-
- if (counter > 0) {
- counter--;
- }
-
- tune_p += tune_p*tune_p_step_ratio;
-
- if (tune_p >= tune_p_max) {
- tune_p = tune_p_max;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- } else {
- ignore_next = false;
- }
- }
- }
- void AC_AutoTune::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)
- {
- if (meas_angle_max < angle_target*(1+0.5f*aggressiveness)) {
- if (ignore_next == false) {
-
- counter++;
- } else {
- ignore_next = false;
- }
- } else {
-
- ignore_next = true;
-
- if (counter > 0) {
- counter--;
- }
-
- tune_p -= tune_p*tune_p_step_ratio;
-
- if (tune_p <= tune_p_min) {
- tune_p = tune_p_min;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- }
- }
- void AC_AutoTune::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)
- {
- if ((meas_angle_max > angle_target*(1+0.5f*aggressiveness)) ||
- ((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max*aggressiveness))) {
-
- ignore_next = true;
-
- counter++;
- } else {
- if (ignore_next == false) {
-
- if (counter > 0) {
- counter--;
- }
-
- tune_p += tune_p*tune_p_step_ratio;
-
- if (tune_p >= tune_p_max) {
- tune_p = tune_p_max;
- counter = AUTOTUNE_SUCCESS_COUNT;
- Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
- }
- } else {
- ignore_next = false;
- }
- }
- }
- bool AC_AutoTune::position_ok(void)
- {
- if (!AP::ahrs().have_inertial_nav()) {
-
- return false;
- }
-
- nav_filter_status filt_status = inertial_nav->get_filter_status();
-
- return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
- }
- void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, float &yaw_cd_out)
- {
- roll_cd_out = pitch_cd_out = 0;
- if (!use_poshold) {
-
- return;
- }
-
- if (!position_ok()) {
- return;
- }
- if (!have_position) {
- have_position = true;
- start_position = inertial_nav->get_position();
- }
-
- const float angle_max_cd = 1000;
-
- const float dist_limit_cm = 2000;
-
-
- const float yaw_dist_limit_cm = 500;
- Vector3f pdiff = inertial_nav->get_position() - start_position;
- pdiff.z = 0;
- float dist_cm = pdiff.length();
- if (dist_cm < 10) {
-
- return;
- }
-
- float scaling = constrain_float(angle_max_cd * dist_cm / dist_limit_cm, 0, angle_max_cd);
- Vector2f angle_ne(pdiff.x, pdiff.y);
- angle_ne *= scaling / dist_cm;
-
- pitch_cd_out = angle_ne.x * ahrs_view->cos_yaw() + angle_ne.y * ahrs_view->sin_yaw();
- roll_cd_out = angle_ne.x * ahrs_view->sin_yaw() - angle_ne.y * ahrs_view->cos_yaw();
- if (dist_cm < yaw_dist_limit_cm) {
-
- return;
- }
-
- float target_yaw_cd = degrees(atan2f(pdiff.y, pdiff.x)) * 100;
- if (axis == PITCH) {
-
-
- target_yaw_cd += 9000;
- }
-
- if (fabsf(yaw_cd_out - target_yaw_cd) > 9500) {
- target_yaw_cd += 18000;
- }
- yaw_cd_out = target_yaw_cd;
- }
- void AC_AutoTune::Log_Write_AutoTune(uint8_t _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)
- {
- AP::logger().Write(
- "ATUN",
- "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt",
- "s--ddd---o",
- "F--000---0",
- "QBBfffffff",
- AP_HAL::micros64(),
- axis,
- tune_step,
- meas_target*0.01f,
- meas_min*0.01f,
- meas_max*0.01f,
- new_gain_rp,
- new_gain_rd,
- new_gain_sp,
- new_ddt);
- }
- void AC_AutoTune::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
- {
- AP::logger().Write(
- "ATDE",
- "TimeUS,Angle,Rate",
- "sdk",
- "F00",
- "Qff",
- AP_HAL::micros64(),
- angle_cd*0.01f,
- rate_cds*0.01f);
- }
|