Path: blob/master/libraries/AC_AutoTune/AC_AutoTune.cpp
9447 views
#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)34{35use_poshold = _use_poshold;36attitude_control = _attitude_control;37pos_control = _pos_control;38ahrs_view = _ahrs_view;39motors = AP_Motors::get_singleton();40const uint32_t now_ms = AP_HAL::millis();4142// exit immediately if motor are not armed43if ((motors == nullptr) || !motors->armed()) {44return false;45}4647// initialise position controller48init_position_controller();4950switch (mode) {51case TuneMode::FAILED:52// Fall through to restart the tuning process from scratch53FALLTHROUGH;5455case TuneMode::UNINITIALISED:56// First-time run: store the current gains as the baseline (original gains)57backup_gains_and_initialise();58// Set the mode to TUNING to begin the autotune process59mode = TuneMode::TUNING;60// Notify GCS that autotune has started61update_gcs(AUTOTUNE_MESSAGE_STARTED);62break;6364case TuneMode::TUNING:65// Resuming from previous tuning session, restart from current axis and tune step66reset_vehicle_test_variables();67step = Step::WAITING_FOR_LEVEL;68step_start_time_ms = now_ms;69level_start_time_ms = now_ms;70// Reload gains with low I-term and restart logging71LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_RESTART);72update_gcs(AUTOTUNE_MESSAGE_STARTED);73break;7475case TuneMode::FINISHED:76case TuneMode::VALIDATING:77// The user is now validating the tuned gains in flight78mode = TuneMode::VALIDATING;79update_gcs(AUTOTUNE_MESSAGE_TESTING);80LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_PILOT_TESTING);81break;82}8384have_position = false;8586return true;87}8889// stop - should be called when the ch7/ch8 switch is switched OFF90void AC_AutoTune::stop()91{92// set gains to their original values93load_gains(GainType::ORIGINAL);9495update_gcs(AUTOTUNE_MESSAGE_STOPPED);9697LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_OFF);9899// Note: we leave the mode as it was so that we know how the autotune ended100// we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch101}102103// Autotune aux function trigger104void AC_AutoTune::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag)105{106if (mode != TuneMode::FINISHED) {107if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {108gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: must be complete to test gains");109}110return;111}112113switch(ch_flag) {114case RC_Channel::AuxSwitchPos::LOW:115// load original gains116load_gains(GainType::ORIGINAL);117update_gcs(AUTOTUNE_MESSAGE_TESTING_END);118break;119case RC_Channel::AuxSwitchPos::MIDDLE:120// Middle position is unused for now_ms121break;122case RC_Channel::AuxSwitchPos::HIGH:123// Load tuned gains124load_gains(GainType::TUNED);125update_gcs(AUTOTUNE_MESSAGE_TESTING);126break;127}128129testing_switch_used = true;130}131132// Possibly save gains, called on disarm133void AC_AutoTune::disarmed(const bool in_autotune_mode)134{135// True if pilot is testing tuned gains136const bool testing_tuned = testing_switch_used && (loaded_gains == GainType::TUNED);137138// True if in autotune mode and no pilot testing commands have been received139const bool tune_complete_no_testing = !testing_switch_used && in_autotune_mode;140141if (tune_complete_no_testing || testing_tuned) {142save_tuning_gains();143} else {144reset();145}146}147148// initialise position controller149bool AC_AutoTune::init_position_controller(void)150{151// initialize vertical maximum speeds and acceleration152init_z_limits();153154// initialise the vertical position controller155pos_control->D_init_controller();156157return true;158}159160void AC_AutoTune::send_step_string()161{162if (pilot_override) {163GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");164return;165}166switch (step) {167case Step::WAITING_FOR_LEVEL:168GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Leveling");169return;170case Step::UPDATE_GAINS:171GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Updating Gains");172return;173case Step::ABORT:174GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Aborting Test");175return;176case Step::EXECUTING_TEST:177GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Testing");178return;179}180GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: unknown step");181}182183const char *AC_AutoTune::get_tune_type_name() const184{185switch (tune_type) {186case TuneType::RATE_D_UP:187return "Rate D Up";188case TuneType::RATE_D_DOWN:189return "Rate D Down";190case TuneType::RATE_P_UP:191return "Rate P Up";192case TuneType::RATE_FF_UP:193return "Rate FF Up";194case TuneType::ANGLE_P_UP:195return "Angle P Up";196case TuneType::ANGLE_P_DOWN:197return "Angle P Down";198case TuneType::MAX_GAINS:199return "Find Max Gains";200case TuneType::TUNE_CHECK:201return "Check Tune Frequency Response";202case TuneType::TUNE_COMPLETE:203return "Tune Complete";204}205return "";206// this should never happen207INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);208}209210// return current axis string211const char *AC_AutoTune::get_axis_name() const212{213switch (axis) {214case AxisType::ROLL:215return "Roll";216case AxisType::PITCH:217return "Pitch";218case AxisType::YAW:219return "Yaw(E)";220case AxisType::YAW_D:221return "Yaw(D)";222}223return "";224}225226// Main update loop for Autotune mode. Handles all states: tuning, validating, or idle.227// Should be called at ≥100Hz for consistent performance.228void AC_AutoTune::run()229{230// Initialise vertical climb rate and acceleration limits231init_z_limits();232233// Exit early if the vehicle is disarmed or motor interlock is not enabled234// (this condition should not occur if init() is working correctly)235if (!motors->armed() || !motors->get_interlock()) {236motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);237attitude_control->set_throttle_out(0.0f, true, 0.0f);238pos_control->D_relax_controller(0.0f);239return;240}241242float desired_yaw_rate_rads; // used during manual control243get_pilot_desired_rp_yrate_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);244245// Get pilot's desired climb rate246const float target_climb_rate_ms = get_desired_climb_rate_ms();247248const bool zero_rp_input = is_zero(desired_roll_rad) && is_zero(desired_pitch_rad);249if (zero_rp_input) {250// Use position hold if enabled251get_poshold_attitude_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rad);252}253254const uint32_t now_ms = AP_HAL::millis();255256switch (mode) {257case TuneMode::TUNING:258// Detect pilot override259if (!zero_rp_input || !is_zero(desired_yaw_rate_rads) || !is_zero(target_climb_rate_ms)) {260if (!pilot_override) {261pilot_override = true;262// Restore original gains while pilot is in control263}264// Update last override time265override_time = now_ms;266if (!zero_rp_input) {267// Invalidate position hold if pilot inputs roll/pitch268have_position = false;269}270} else if (pilot_override) {271// Check if pilot has released sticks long enough to resume tuning272if (now_ms - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) {273pilot_override = false;274step = Step::WAITING_FOR_LEVEL;275step_start_time_ms = now_ms;276level_start_time_ms = now_ms;277// TODO: Consider using our current target.278desired_yaw_rad = ahrs_view->get_yaw_rad(); // Reset yaw reference279}280}281282if (pilot_override) {283// Pilot is actively controlling the vehicle; fly on original gains284if (now_ms - last_pilot_override_warning > 1000) {285GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: pilot overrides active");286last_pilot_override_warning = now_ms;287}288load_gains(GainType::ORIGINAL);289attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);290} else {291// Autotune controls the aircraft292control_attitude();293do_gcs_announcements();294}295break;296297case TuneMode::UNINITIALISED:298// Should never reach this state; init() must be called before run()299INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);300FALLTHROUGH;301302case TuneMode::FAILED:303FALLTHROUGH;304305case TuneMode::FINISHED:306// Tuning is complete or failed; fly using original gains307load_gains(GainType::ORIGINAL);308attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);309break;310311case TuneMode::VALIDATING:312// Pilot is evaluating tuned gains313load_gains(GainType::TUNED);314attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);315break;316}317318motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);319320// Update vertical position controller with pilot climb rate input321pos_control->D_set_pos_target_from_climb_rate_ms(target_climb_rate_ms);322pos_control->D_update_controller();323}324325// return true if vehicle is close to level326bool AC_AutoTune::currently_level()327{328// abort AutoTune if we pass 2 * AUTOTUNE_LEVEL_TIMEOUT_MS329const uint32_t now_ms = AP_HAL::millis();330if (now_ms - level_start_time_ms > 3 * AUTOTUNE_LEVEL_TIMEOUT_MS) {331GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Failed to level, please tune manually");332mode = TuneMode::FAILED;333LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);334}335336// slew threshold to ensure sufficient settling time for aircraft unable to obtain small thresholds337// relax threshold if we pass AUTOTUNE_LEVEL_TIMEOUT_MS338const float threshold_mul = constrain_float((float)(now_ms - level_start_time_ms) / (float)AUTOTUNE_LEVEL_TIMEOUT_MS, 0.0, 2.0);339340if (fabsf(ahrs_view->get_roll_rad() - desired_roll_rad) > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_ANGLE_CD)) {341return false;342}343if (fabsf(ahrs_view->get_pitch_rad() - desired_pitch_rad) > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_ANGLE_CD)) {344return false;345}346if (fabsf(wrap_PI(ahrs_view->get_yaw_rad() - desired_yaw_rad)) > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_ANGLE_CD)) {347return false;348}349if (ahrs_view->get_gyro().x > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_RATE_RP_CD)) {350return false;351}352if (ahrs_view->get_gyro().y > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_RATE_RP_CD)) {353return false;354}355if (ahrs_view->get_gyro().z > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_RATE_Y_CD)) {356return false;357}358return true;359}360361// Main tuning state machine. Handles all StepTypes: WAITING_FOR_LEVEL, EXECUTING_TEST, UPDATE_GAINS, ABORT.362// Updates attitude controller targets and processes test results to adjust PID gains.363void AC_AutoTune::control_attitude()364{365rotation_rate = 0.0f;366lean_angle = 0.0f;367const float direction_sign = positive_direction ? 1.0f : -1.0f;368const uint32_t now_ms = AP_HAL::millis();369370switch (step) {371372case Step::WAITING_FOR_LEVEL: {373// Use intra-test gains while holding level between tests374load_gains(GainType::INTRA_TEST);375376attitude_control->input_euler_angle_roll_pitch_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rad, true);377378// Require a short stable period before executing the next test379if (!currently_level()) {380step_start_time_ms = now_ms;381}382383if (now_ms - step_start_time_ms > AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {384// Begin the test phase385step = Step::EXECUTING_TEST;386step_start_time_ms = now_ms;387step_timeout_ms = get_testing_step_timeout_ms();388389// Record starting angular position and rate390switch (axis) {391case AxisType::ROLL:392start_rate = degrees(ahrs_view->get_gyro().x) * 100.0f;393start_angle = ahrs_view->roll_sensor;394break;395case AxisType::PITCH:396start_rate = degrees(ahrs_view->get_gyro().y) * 100.0f;397start_angle = ahrs_view->pitch_sensor;398break;399case AxisType::YAW:400case AxisType::YAW_D:401start_rate = degrees(ahrs_view->get_gyro().z) * 100.0f;402start_angle = ahrs_view->yaw_sensor;403break;404}405406// Apply test gains and initialise test-specific variables407load_gains(GainType::TEST);408test_init();409}410break;411}412413case Step::EXECUTING_TEST: {414// Run the test with current trial gains415load_gains(GainType::TEST);416test_run(axis, direction_sign);417418// Detect failure due to reverse response or excessive lean angle419if (lean_angle <= -angle_lim_neg_rpy_cd() ||420attitude_control->lean_angle_deg() * 100 > angle_lim_max_rp_cd()) {421step = Step::ABORT;422}423424#if HAL_LOGGING_ENABLED425Log_AutoTuneDetails();426attitude_control->Write_Rate(*pos_control);427log_pids();428#endif429430// Update yaw target for next test if required431if (axis == AxisType::YAW || axis == AxisType::YAW_D) {432desired_yaw_rad = ahrs_view->get_yaw_rad();433}434break;435}436437case Step::UPDATE_GAINS:438439#if HAL_LOGGING_ENABLED440Log_AutoTune(); // Log gain adjustment results441#endif442443// Announce test results before gains are changed444do_post_test_gcs_announcements();445446// Update gains based on the current tuning strategy447switch (tune_type) {448case TuneType::RATE_D_UP:449updating_rate_d_up_all(axis);450break;451case TuneType::RATE_D_DOWN:452updating_rate_d_down_all(axis);453break;454case TuneType::RATE_P_UP:455updating_rate_p_up_all(axis);456break;457case TuneType::ANGLE_P_DOWN:458updating_angle_p_down_all(axis);459break;460case TuneType::ANGLE_P_UP:461updating_angle_p_up_all(axis);462break;463case TuneType::RATE_FF_UP:464updating_rate_ff_up_all(axis);465break;466case TuneType::MAX_GAINS:467updating_max_gains_all(axis);468break;469case TuneType::TUNE_CHECK:470success_counter = AUTOTUNE_SUCCESS_COUNT;471FALLTHROUGH;472case TuneType::TUNE_COMPLETE:473break;474}475476// If tuning step was successful, proceed to the next step477if (success_counter >= AUTOTUNE_SUCCESS_COUNT) {478success_counter = 0;479step_scaler = 1.0f;480set_tuning_gains_with_backoff(axis);481next_tune_type(tune_type, false);482483if (tune_type == TuneType::TUNE_COMPLETE) {484// Complete tuning for this axis and determine the next one485next_tune_type(tune_type, true);486report_final_gains(axis);487488bool complete = false;489switch (axis) {490case AxisType::ROLL:491axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL;492if (pitch_enabled()) {493axis = AxisType::PITCH;494} else if (yaw_enabled()) {495axis = AxisType::YAW;496} else if (yaw_d_enabled()) {497axis = AxisType::YAW_D;498} else {499complete = true;500}501break;502case AxisType::PITCH:503axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH;504if (yaw_enabled()) {505axis = AxisType::YAW;506} else if (yaw_d_enabled()) {507axis = AxisType::YAW_D;508} else {509complete = true;510}511break;512case AxisType::YAW:513axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW;514if (yaw_d_enabled()) {515axis = AxisType::YAW_D;516} else {517complete = true;518}519break;520case AxisType::YAW_D:521axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW_D;522complete = true;523break;524}525526if (complete) {527mode = TuneMode::FINISHED;528update_gcs(AUTOTUNE_MESSAGE_SUCCESS);529LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SUCCESS);530AP_Notify::events.autotune_complete = true;531load_gains(GainType::ORIGINAL); // Reset for landing532} else {533AP_Notify::events.autotune_next_axis = true;534reset_update_gain_variables();535}536}537}538FALLTHROUGH;539540case Step::ABORT:541// Recover from failed test or move on after a successful one542543attitude_control->input_euler_angle_roll_pitch_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rad, true);544545load_gains(GainType::INTRA_TEST);546547step = Step::WAITING_FOR_LEVEL;548positive_direction = reverse_test_direction();549step_start_time_ms = now_ms;550level_start_time_ms = now_ms;551step_timeout_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS;552break;553}554}555556// backup_gains_and_initialise - store current gains as originals557// called before tuning starts to backup original gains558void AC_AutoTune::backup_gains_and_initialise()559{560const uint32_t now_ms = AP_HAL::millis();561562// initialise state because this is our first time563if (roll_enabled()) {564axis = AxisType::ROLL;565} else if (pitch_enabled()) {566axis = AxisType::PITCH;567} else if (yaw_enabled()) {568axis = AxisType::YAW;569} else if (yaw_d_enabled()) {570axis = AxisType::YAW_D;571}572// no axes are complete573axes_completed = 0;574575// reset update gain variables for each vehicle576reset_update_gain_variables();577578// start at the beginning of tune sequence579next_tune_type(tune_type, true);580581step = Step::WAITING_FOR_LEVEL;582positive_direction = false;583step_start_time_ms = now_ms;584level_start_time_ms = now_ms;585step_scaler = 1.0f;586587desired_yaw_rad = ahrs_view->get_yaw_rad();588}589590/*591load a specified set of gains592*/593void AC_AutoTune::load_gains(enum GainType gain_type)594{595if (loaded_gains == gain_type) {596// Loaded gains are already of correct type597return;598}599loaded_gains = gain_type;600601switch (gain_type) {602case GainType::ORIGINAL:603load_orig_gains();604break;605case GainType::INTRA_TEST:606load_intra_test_gains();607break;608case GainType::TEST:609load_test_gains();610break;611case GainType::TUNED:612load_tuned_gains();613break;614}615}616617// update_gcs - send message to ground station618void AC_AutoTune::update_gcs(uint8_t message_id) const619{620switch (message_id) {621case AUTOTUNE_MESSAGE_STARTED:622GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Started");623break;624case AUTOTUNE_MESSAGE_STOPPED:625GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Stopped");626break;627case AUTOTUNE_MESSAGE_SUCCESS:628GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Success");629break;630case AUTOTUNE_MESSAGE_FAILED:631GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Failed");632break;633case AUTOTUNE_MESSAGE_TESTING:634case AUTOTUNE_MESSAGE_SAVED_GAINS:635GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s gains for %s%s%s%s",636(message_id == AUTOTUNE_MESSAGE_SAVED_GAINS) ? "Saved" : "Pilot Testing",637(axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"",638(axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"",639(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw(E)":"",640(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW_D)?"Yaw(D)":"");641break;642case AUTOTUNE_MESSAGE_TESTING_END:643GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: original gains restored");644break;645}646}647648// axis helper functions649bool AC_AutoTune::roll_enabled() const650{651return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_ROLL;652}653654bool AC_AutoTune::pitch_enabled() const655{656return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_PITCH;657}658659bool AC_AutoTune::yaw_enabled() const660{661return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW;662}663664bool AC_AutoTune::yaw_d_enabled() const665{666#if APM_BUILD_TYPE(APM_BUILD_Heli)667return false;668#else669return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW_D;670#endif671}672673/*674check if we have a good position estimate675*/676bool AC_AutoTune::position_ok(void)677{678if (!AP::ahrs().have_inertial_nav()) {679// do not allow navigation with dcm position680return false;681}682683// with EKF use filter status and ekf check684nav_filter_status filt_status {};685AP::ahrs().get_filter_status(filt_status);686687// require a good absolute position and EKF must not be in const_pos_mode688return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);689}690691// get attitude for slow position hold in autotune mode692void AC_AutoTune::get_poshold_attitude_rad(float &roll_out_rad, float &pitch_out_rad, float &yaw_out_rad)693{694roll_out_rad = pitch_out_rad = 0;695696if (!use_poshold) {697// we are not trying to hold position698return;699}700701// do we know where we are? If not then don't do poshold702if (!position_ok()) {703return;704}705706if (!have_position) {707have_position = true;708start_position_ned_m = pos_control->get_pos_estimate_NED_m();709}710711// don't go past 10 degrees, as autotune result would deteriorate too much712const float angle_max_rad = radians(10.0);713714// hit the 10 degree limit at 20 meters position error715const float dist_limit_m = 20.00;716717// we only start adjusting yaw if we are more than 5m from the718// target position. That corresponds to a lean angle of 2.5 degrees719const float yaw_dist_limit_m = 5.0;720721Vector3f pos_error_ned_m = (pos_control->get_pos_estimate_NED_m() - start_position_ned_m).tofloat();722pos_error_ned_m.z = 0;723float dist_m = pos_error_ned_m.length();724if (dist_m < 0.10) {725// don't do anything within 10cm726return;727}728729/*730very simple linear controller731*/732float scaling = constrain_float(angle_max_rad * dist_m / dist_limit_m, 0, angle_max_rad);733Vector2f angle_ne(pos_error_ned_m.x, pos_error_ned_m.y);734angle_ne *= scaling / dist_m;735736// rotate into body frame737pitch_out_rad = angle_ne.x * ahrs_view->cos_yaw() + angle_ne.y * ahrs_view->sin_yaw();738roll_out_rad = angle_ne.x * ahrs_view->sin_yaw() - angle_ne.y * ahrs_view->cos_yaw();739740if (dist_m < yaw_dist_limit_m) {741// no yaw adjustment742return;743}744745/*746also point so that test occurs perpendicular to the wind,747if we have drifted more than yaw_dist_limit_m from the desired748position. This ensures that autotune doesn't have to deal with749more than 2.5 degrees of attitude on the axis it is tuning750*/751float target_yaw_rad = atan2f(pos_error_ned_m.y, pos_error_ned_m.x);752if (axis == AxisType::PITCH) {753// for roll and yaw tuning we point along the wind, for pitch754// we point across the wind755target_yaw_rad += radians(90);756}757// go to the nearest 180 degree mark, with 5 degree slop to prevent oscillation758if (fabsf(yaw_out_rad - target_yaw_rad) > radians(95.0)) {759target_yaw_rad += radians(180.0);760}761762yaw_out_rad = target_yaw_rad;763}764765// get the next tune type766void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset)767{768if (reset) {769set_tune_sequence();770tune_seq_index = 0;771} else if (curr_tune_type == TuneType::TUNE_COMPLETE) {772// leave tune_type as TUNE_COMPLETE to initiate next axis or exit autotune773return;774} else {775tune_seq_index++;776}777778curr_tune_type = tune_seq[tune_seq_index];779}780781#endif // AC_AUTOTUNE_ENABLED782783784