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.cpp
Views: 1798
#include "AC_AutoTune_config.h"12#if AC_AUTOTUNE_ENABLED34#include "AC_AutoTune.h"56#include <AP_Logger/AP_Logger.h>7#include <AP_Scheduler/AP_Scheduler.h>8#include <AP_Notify/AP_Notify.h>9#include <GCS_MAVLink/GCS.h>10#include <AP_Vehicle/AP_Vehicle_Type.h>1112#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds13#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)14# define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg)15# define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec)16#else17# define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level18# define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch19#endif20#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw21#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 250 // time we require the aircraft to be level before starting next test22#define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level23#define AUTOTUNE_LEVEL_WARNING_INTERVAL_MS 5000 // level failure warning messages sent at this interval to users2425AC_AutoTune::AC_AutoTune()26{27}2829// autotune_init - should be called when autotune mode is selected30bool AC_AutoTune::init_internals(bool _use_poshold,31AC_AttitudeControl *_attitude_control,32AC_PosControl *_pos_control,33AP_AHRS_View *_ahrs_view,34AP_InertialNav *_inertial_nav)35{36use_poshold = _use_poshold;37attitude_control = _attitude_control;38pos_control = _pos_control;39ahrs_view = _ahrs_view;40inertial_nav = _inertial_nav;41motors = AP_Motors::get_singleton();42const uint32_t now = AP_HAL::millis();4344// exit immediately if motor are not armed45if ((motors == nullptr) || !motors->armed()) {46return false;47}4849// initialise position controller50init_position_controller();5152switch (mode) {53case FAILED:54// fall through to restart the tuning55FALLTHROUGH;5657case UNINITIALISED:58// autotune has never been run59// so store current gains as original gains60backup_gains_and_initialise();61// advance mode to tuning62mode = TUNING;63// send message to ground station that we've started tuning64update_gcs(AUTOTUNE_MESSAGE_STARTED);65break;6667case TUNING:68// reset test variables for each vehicle69reset_vehicle_test_variables();7071// we are restarting tuning so restart where we left off72step = WAITING_FOR_LEVEL;73step_start_time_ms = now;74level_start_time_ms = now;75// reset gains to tuning-start gains (i.e. low I term)76load_gains(GAIN_INTRA_TEST);77LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_RESTART);78update_gcs(AUTOTUNE_MESSAGE_STARTED);79break;8081case SUCCESS:82// we have completed a tune and the pilot wishes to test the new gains83load_gains(GAIN_TUNED);84update_gcs(AUTOTUNE_MESSAGE_TESTING);85LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_PILOT_TESTING);86break;87}8889have_position = false;9091return true;92}9394// stop - should be called when the ch7/ch8 switch is switched OFF95void AC_AutoTune::stop()96{97// set gains to their original values98load_gains(GAIN_ORIGINAL);99100// re-enable angle-to-rate request limits101attitude_control->use_sqrt_controller(true);102103update_gcs(AUTOTUNE_MESSAGE_STOPPED);104105LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_OFF);106107// Note: we leave the mode as it was so that we know how the autotune ended108// we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch109}110111// Autotune aux function trigger112void AC_AutoTune::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag)113{114if (mode != TuneMode::SUCCESS) {115if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {116gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: must be complete to test gains");117}118return;119}120121switch(ch_flag) {122case RC_Channel::AuxSwitchPos::LOW:123// load original gains124load_gains(GainType::GAIN_ORIGINAL);125update_gcs(AUTOTUNE_MESSAGE_TESTING_END);126break;127case RC_Channel::AuxSwitchPos::MIDDLE:128// Middle position is unused for now129break;130case RC_Channel::AuxSwitchPos::HIGH:131// Load tuned gains132load_gains(GainType::GAIN_TUNED);133update_gcs(AUTOTUNE_MESSAGE_TESTING);134break;135}136137have_pilot_testing_command = true;138}139140// Possibly save gains, called on disarm141void AC_AutoTune::disarmed(const bool in_autotune_mode)142{143// True if pilot is testing tuned gains144const bool testing_tuned = have_pilot_testing_command && (loaded_gains == GainType::GAIN_TUNED);145146// True if in autotune mode and no pilot testing commands have been received147const bool tune_complete_no_testing = !have_pilot_testing_command && in_autotune_mode;148149if (tune_complete_no_testing || testing_tuned) {150save_tuning_gains();151} else {152reset();153}154}155156// initialise position controller157bool AC_AutoTune::init_position_controller(void)158{159// initialize vertical maximum speeds and acceleration160init_z_limits();161162// initialise the vertical position controller163pos_control->init_z_controller();164165return true;166}167168void AC_AutoTune::send_step_string()169{170if (pilot_override) {171GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");172return;173}174switch (step) {175case WAITING_FOR_LEVEL:176GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Leveling");177return;178case UPDATE_GAINS:179GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Updating Gains");180return;181case ABORT:182GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Aborting Test");183return;184case TESTING:185GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Testing");186return;187}188GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: unknown step");189}190191const char *AC_AutoTune::type_string() const192{193switch (tune_type) {194case RD_UP:195return "Rate D Up";196case RD_DOWN:197return "Rate D Down";198case RP_UP:199return "Rate P Up";200case RFF_UP:201return "Rate FF Up";202case SP_UP:203return "Angle P Up";204case SP_DOWN:205return "Angle P Down";206case MAX_GAINS:207return "Find Max Gains";208case TUNE_CHECK:209return "Check Tune Frequency Response";210case TUNE_COMPLETE:211return "Tune Complete";212}213return "";214// this should never happen215INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);216}217218// return current axis string219const char *AC_AutoTune::axis_string() const220{221switch (axis) {222case AxisType::ROLL:223return "Roll";224case AxisType::PITCH:225return "Pitch";226case AxisType::YAW:227return "Yaw(E)";228case AxisType::YAW_D:229return "Yaw(D)";230}231return "";232}233234// run - runs the autotune flight mode235// should be called at 100hz or more236void AC_AutoTune::run()237{238// initialize vertical speeds and acceleration239init_z_limits();240241// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately242// this should not actually be possible because of the init() checks243if (!motors->armed() || !motors->get_interlock()) {244motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);245attitude_control->set_throttle_out(0.0f, true, 0.0f);246pos_control->relax_z_controller(0.0f);247return;248}249250float target_roll_cd, target_pitch_cd, target_yaw_rate_cds;251get_pilot_desired_rp_yrate_cd(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);252253// get pilot desired climb rate254const float target_climb_rate_cms = get_pilot_desired_climb_rate_cms();255256const bool zero_rp_input = is_zero(target_roll_cd) && is_zero(target_pitch_cd);257258const uint32_t now = AP_HAL::millis();259260if (mode != SUCCESS) {261if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) {262if (!pilot_override) {263pilot_override = true;264// set gains to their original values265load_gains(GAIN_ORIGINAL);266attitude_control->use_sqrt_controller(true);267}268// reset pilot override time269override_time = now;270if (!zero_rp_input) {271// only reset position on roll or pitch input272have_position = false;273}274} else if (pilot_override) {275// check if we should resume tuning after pilot's override276if (now - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) {277pilot_override = false; // turn off pilot override278// set gains to their intra-test values (which are very close to the original gains)279// load_gains(GAIN_INTRA_TEST); //I think we should be keeping the originals here to let the I term settle quickly280step = WAITING_FOR_LEVEL; // set tuning step back from beginning281step_start_time_ms = now;282level_start_time_ms = now;283desired_yaw_cd = ahrs_view->yaw_sensor;284}285}286}287if (pilot_override) {288if (now - last_pilot_override_warning > 1000) {289GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: pilot overrides active");290last_pilot_override_warning = now;291}292}293if (zero_rp_input) {294// pilot input on throttle and yaw will still use position hold if enabled295get_poshold_attitude(target_roll_cd, target_pitch_cd, desired_yaw_cd);296}297298// set motors to full range299motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);300301// if pilot override call attitude controller302if (pilot_override || mode != TUNING) {303attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);304} else {305// somehow get attitude requests from autotuning306control_attitude();307// tell the user what's going on308do_gcs_announcements();309}310311// call position controller312pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cms);313pos_control->update_z_controller();314315}316317// return true if vehicle is close to level318bool AC_AutoTune::currently_level()319{320// abort AutoTune if we pass 2 * AUTOTUNE_LEVEL_TIMEOUT_MS321const uint32_t now_ms = AP_HAL::millis();322if (now_ms - level_start_time_ms > 3 * AUTOTUNE_LEVEL_TIMEOUT_MS) {323GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Failed to level, please tune manually");324mode = FAILED;325LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);326}327328// slew threshold to ensure sufficient settling time for aircraft unable to obtain small thresholds329// relax threshold if we pass AUTOTUNE_LEVEL_TIMEOUT_MS330const float threshold_mul = constrain_float((float)(now_ms - level_start_time_ms) / (float)AUTOTUNE_LEVEL_TIMEOUT_MS, 0.0, 2.0);331332if (fabsf(ahrs_view->roll_sensor - roll_cd) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) {333return false;334}335336if (fabsf(ahrs_view->pitch_sensor - pitch_cd) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) {337return false;338}339if (fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) {340return false;341}342if ((ToDeg(ahrs_view->get_gyro().x) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_RP_CD) {343return false;344}345if ((ToDeg(ahrs_view->get_gyro().y) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_RP_CD) {346return false;347}348if ((ToDeg(ahrs_view->get_gyro().z) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_Y_CD) {349return false;350}351return true;352}353354// main state machine to level vehicle, perform a test and update gains355// directly updates attitude controller with targets356void AC_AutoTune::control_attitude()357{358rotation_rate = 0.0f; // rotation rate in radians/second359lean_angle = 0.0f;360const float direction_sign = positive_direction ? 1.0f : -1.0f;361const uint32_t now = AP_HAL::millis();362363// check tuning step364switch (step) {365366case WAITING_FOR_LEVEL: {367368// Note: we should be using intra-test gains (which are very close to the original gains but have lower I)369// re-enable rate limits370attitude_control->use_sqrt_controller(true);371372get_poshold_attitude(roll_cd, pitch_cd, desired_yaw_cd);373374// hold level attitude375attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true);376377// hold the copter level for 0.5 seconds before we begin a twitch378// reset counter if we are no longer level379if (!currently_level()) {380step_start_time_ms = now;381}382383// if we have been level for a sufficient amount of time (0.5 seconds) move onto tuning step384if (now - step_start_time_ms > AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {385// initiate variables for next step386step = TESTING;387step_start_time_ms = now;388step_time_limit_ms = get_testing_step_timeout_ms();389// set gains to their to-be-tested values390load_gains(GAIN_TEST);391} else {392// when waiting for level we use the intra-test gains393load_gains(GAIN_INTRA_TEST);394}395396// Initialize test-specific variables397switch (axis) {398case AxisType::ROLL:399start_rate = ToDeg(ahrs_view->get_gyro().x) * 100.0f;400start_angle = ahrs_view->roll_sensor;401break;402case AxisType::PITCH:403start_rate = ToDeg(ahrs_view->get_gyro().y) * 100.0f;404start_angle = ahrs_view->pitch_sensor;405break;406case AxisType::YAW:407case AxisType::YAW_D:408start_rate = ToDeg(ahrs_view->get_gyro().z) * 100.0f;409start_angle = ahrs_view->yaw_sensor;410break;411}412413// tests must be initialized last as some rely on variables above414test_init();415416break;417}418419case TESTING: {420// Run the twitching step421load_gains(GAIN_TEST);422423// run the test424test_run(axis, direction_sign);425426// Check for failure causing reverse response427if (lean_angle <= -angle_lim_neg_rpy_cd()) {428step = WAITING_FOR_LEVEL;429positive_direction = twitch_reverse_direction();430step_start_time_ms = now;431level_start_time_ms = now;432}433434// protect from roll over435if (attitude_control->lean_angle_deg() * 100 > angle_lim_max_rp_cd()) {436step = WAITING_FOR_LEVEL;437positive_direction = twitch_reverse_direction();438step_start_time_ms = now;439level_start_time_ms = now;440}441442#if HAL_LOGGING_ENABLED443// log this iterations lean angle and rotation rate444Log_AutoTuneDetails();445attitude_control->Write_Rate(*pos_control);446log_pids();447#endif448449if (axis == AxisType::YAW || axis == AxisType::YAW_D) {450desired_yaw_cd = ahrs_view->yaw_sensor;451}452break;453}454455case UPDATE_GAINS:456457// re-enable rate limits458attitude_control->use_sqrt_controller(true);459460#if HAL_LOGGING_ENABLED461// log the latest gains462Log_AutoTune();463#endif464465// Announce tune type test results466// must be done before updating method because this method changes parameters for next test467do_post_test_gcs_announcements();468469switch (tune_type) {470// Check results after mini-step to increase rate D gain471case RD_UP:472updating_rate_d_up_all(axis);473break;474// Check results after mini-step to decrease rate D gain475case RD_DOWN:476updating_rate_d_down_all(axis);477break;478// Check results after mini-step to increase rate P gain479case RP_UP:480updating_rate_p_up_all(axis);481break;482// Check results after mini-step to increase stabilize P gain483case SP_DOWN:484updating_angle_p_down_all(axis);485break;486// Check results after mini-step to increase stabilize P gain487case SP_UP:488updating_angle_p_up_all(axis);489break;490case RFF_UP:491updating_rate_ff_up_all(axis);492break;493case MAX_GAINS:494updating_max_gains_all(axis);495break;496case TUNE_CHECK:497counter = AUTOTUNE_SUCCESS_COUNT;498FALLTHROUGH;499case TUNE_COMPLETE:500break;501}502503// we've complete this step, finalize pids and move to next step504if (counter >= AUTOTUNE_SUCCESS_COUNT) {505506// reset counter507counter = 0;508509// reset scaling factor510step_scaler = 1.0f;511512513// set gains for post tune before moving to the next tuning type514set_gains_post_tune(axis);515516// increment the tune type to the next one in tune sequence517next_tune_type(tune_type, false);518519if (tune_type == TUNE_COMPLETE) {520// we've reached the end of a D-up-down PI-up-down tune type cycle521next_tune_type(tune_type, true);522523report_final_gains(axis);524525// advance to the next axis526bool complete = false;527switch (axis) {528case AxisType::ROLL:529axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL;530if (pitch_enabled()) {531axis = AxisType::PITCH;532} else if (yaw_enabled()) {533axis = AxisType::YAW;534} else if (yaw_d_enabled()) {535axis = AxisType::YAW_D;536} else {537complete = true;538}539break;540case AxisType::PITCH:541axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH;542if (yaw_enabled()) {543axis = AxisType::YAW;544} else if (yaw_d_enabled()) {545axis = AxisType::YAW_D;546} else {547complete = true;548}549break;550case AxisType::YAW:551axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW;552if (yaw_d_enabled()) {553axis = AxisType::YAW_D;554} else {555complete = true;556}557break;558case AxisType::YAW_D:559axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW_D;560complete = true;561break;562}563564// if we've just completed all axes we have successfully completed the autotune565// change to TESTING mode to allow user to fly with new gains566if (complete) {567mode = SUCCESS;568update_gcs(AUTOTUNE_MESSAGE_SUCCESS);569LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SUCCESS);570AP_Notify::events.autotune_complete = true;571572// Return to original gains for landing573load_gains(GainType::GAIN_ORIGINAL);574} else {575AP_Notify::events.autotune_next_axis = true;576reset_update_gain_variables();577}578}579}580FALLTHROUGH;581582case ABORT:583if (axis == AxisType::YAW || axis == AxisType::YAW_D) {584// todo: check to make sure we need this585attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs_view->yaw_sensor, false);586}587588// set gains to their intra-test values (which are very close to the original gains)589load_gains(GAIN_INTRA_TEST);590591// reset testing step592step = WAITING_FOR_LEVEL;593positive_direction = twitch_reverse_direction();594step_start_time_ms = now;595level_start_time_ms = now;596step_time_limit_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS;597break;598}599}600601// backup_gains_and_initialise - store current gains as originals602// called before tuning starts to backup original gains603void AC_AutoTune::backup_gains_and_initialise()604{605const uint32_t now = AP_HAL::millis();606607// initialise state because this is our first time608if (roll_enabled()) {609axis = AxisType::ROLL;610} else if (pitch_enabled()) {611axis = AxisType::PITCH;612} else if (yaw_enabled()) {613axis = AxisType::YAW;614} else if (yaw_d_enabled()) {615axis = AxisType::YAW_D;616}617// no axes are complete618axes_completed = 0;619620// reset update gain variables for each vehicle621reset_update_gain_variables();622623// start at the beginning of tune sequence624next_tune_type(tune_type, true);625626step = WAITING_FOR_LEVEL;627positive_direction = false;628step_start_time_ms = now;629level_start_time_ms = now;630step_scaler = 1.0f;631632desired_yaw_cd = ahrs_view->yaw_sensor;633}634635/*636load a specified set of gains637*/638void AC_AutoTune::load_gains(enum GainType gain_type)639{640if (loaded_gains == gain_type) {641// Loaded gains are already of correct type642return;643}644loaded_gains = gain_type;645646switch (gain_type) {647case GAIN_ORIGINAL:648load_orig_gains();649break;650case GAIN_INTRA_TEST:651load_intra_test_gains();652break;653case GAIN_TEST:654load_test_gains();655break;656case GAIN_TUNED:657load_tuned_gains();658break;659}660}661662// update_gcs - send message to ground station663void AC_AutoTune::update_gcs(uint8_t message_id) const664{665switch (message_id) {666case AUTOTUNE_MESSAGE_STARTED:667GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Started");668break;669case AUTOTUNE_MESSAGE_STOPPED:670GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Stopped");671break;672case AUTOTUNE_MESSAGE_SUCCESS:673GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Success");674break;675case AUTOTUNE_MESSAGE_FAILED:676GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Failed");677break;678case AUTOTUNE_MESSAGE_TESTING:679case AUTOTUNE_MESSAGE_SAVED_GAINS:680GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s gains for %s%s%s%s",681(message_id == AUTOTUNE_MESSAGE_SAVED_GAINS) ? "Saved" : "Pilot Testing",682(axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"",683(axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"",684(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw(E)":"",685(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW_D)?"Yaw(D)":"");686break;687case AUTOTUNE_MESSAGE_TESTING_END:688GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: original gains restored");689break;690}691}692693// axis helper functions694bool AC_AutoTune::roll_enabled() const695{696return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_ROLL;697}698699bool AC_AutoTune::pitch_enabled() const700{701return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_PITCH;702}703704bool AC_AutoTune::yaw_enabled() const705{706return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW;707}708709bool AC_AutoTune::yaw_d_enabled() const710{711#if APM_BUILD_TYPE(APM_BUILD_Heli)712return false;713#else714return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW_D;715#endif716}717718/*719check if we have a good position estimate720*/721bool AC_AutoTune::position_ok(void)722{723if (!AP::ahrs().have_inertial_nav()) {724// do not allow navigation with dcm position725return false;726}727728// with EKF use filter status and ekf check729nav_filter_status filt_status = inertial_nav->get_filter_status();730731// require a good absolute position and EKF must not be in const_pos_mode732return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);733}734735// get attitude for slow position hold in autotune mode736void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, float &yaw_cd_out)737{738roll_cd_out = pitch_cd_out = 0;739740if (!use_poshold) {741// we are not trying to hold position742return;743}744745// do we know where we are? If not then don't do poshold746if (!position_ok()) {747return;748}749750if (!have_position) {751have_position = true;752start_position = inertial_nav->get_position_neu_cm();753}754755// don't go past 10 degrees, as autotune result would deteriorate too much756const float angle_max_cd = 1000;757758// hit the 10 degree limit at 20 meters position error759const float dist_limit_cm = 2000;760761// we only start adjusting yaw if we are more than 5m from the762// target position. That corresponds to a lean angle of 2.5 degrees763const float yaw_dist_limit_cm = 500;764765Vector3f pdiff = inertial_nav->get_position_neu_cm() - start_position;766pdiff.z = 0;767float dist_cm = pdiff.length();768if (dist_cm < 10) {769// don't do anything within 10cm770return;771}772773/*774very simple linear controller775*/776float scaling = constrain_float(angle_max_cd * dist_cm / dist_limit_cm, 0, angle_max_cd);777Vector2f angle_ne(pdiff.x, pdiff.y);778angle_ne *= scaling / dist_cm;779780// rotate into body frame781pitch_cd_out = angle_ne.x * ahrs_view->cos_yaw() + angle_ne.y * ahrs_view->sin_yaw();782roll_cd_out = angle_ne.x * ahrs_view->sin_yaw() - angle_ne.y * ahrs_view->cos_yaw();783784if (dist_cm < yaw_dist_limit_cm) {785// no yaw adjustment786return;787}788789/*790also point so that twitching occurs perpendicular to the wind,791if we have drifted more than yaw_dist_limit_cm from the desired792position. This ensures that autotune doesn't have to deal with793more than 2.5 degrees of attitude on the axis it is tuning794*/795float target_yaw_cd = degrees(atan2f(pdiff.y, pdiff.x)) * 100;796if (axis == AxisType::PITCH) {797// for roll and yaw tuning we point along the wind, for pitch798// we point across the wind799target_yaw_cd += 9000;800}801// go to the nearest 180 degree mark, with 5 degree slop to prevent oscillation802if (fabsf(yaw_cd_out - target_yaw_cd) > 9500) {803target_yaw_cd += 18000;804}805806yaw_cd_out = target_yaw_cd;807}808809// get the next tune type810void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset)811{812if (reset) {813set_tune_sequence();814tune_seq_curr = 0;815} else if (curr_tune_type == TUNE_COMPLETE) {816// leave tune_type as TUNE_COMPLETE to initiate next axis or exit autotune817return;818} else {819tune_seq_curr++;820}821822curr_tune_type = tune_seq[tune_seq_curr];823}824825#endif // AC_AUTOTUNE_ENABLED826827828