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_Heli.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15support for autotune of helicopters16*/1718#pragma once1920#include "AC_AutoTune_config.h"2122#if AC_AUTOTUNE_ENABLED2324#include "AC_AutoTune.h"25#include <AP_Math/chirp.h>26#include <GCS_MAVLink/GCS.h>2728#include <AP_Scheduler/AP_Scheduler.h>2930class AC_AutoTune_Heli : public AC_AutoTune31{32public:33// constructor34AC_AutoTune_Heli();3536// save gained, called on disarm37void save_tuning_gains() override;3839// var_info for holding Parameter information40static const struct AP_Param::GroupInfo var_info[];4142protected:4344//45// methods to load and save gains46//4748// backup original gains and prepare for start of tuning49void backup_gains_and_initialise() override;5051// load gains52void load_gain_set(AxisType s_axis, float rate_p, float rate_i, float rate_d, float rate_ff, float angle_p, float max_accel, float rate_fltt, float rate_flte, float smax, float max_rate);5354// switch to use original gains55void load_orig_gains() override;5657// switch to gains found by last successful autotune58void load_tuned_gains() override;5960// load gains used between tests. called during testing mode's update-gains step to set gains ahead of return-to-level step61void load_intra_test_gains() override;6263// load test gains64void load_test_gains() override;6566// reset the test variables for heli67void reset_vehicle_test_variables() override;6869// reset the update gain variables for heli70void reset_update_gain_variables() override;7172// initializes test73void test_init() override;7475// runs test76void test_run(AxisType test_axis, const float dir_sign) override;7778// update gains for the rate p up tune type79void updating_rate_p_up_all(AxisType test_axis) override;8081// update gains for the rate d up tune type82void updating_rate_d_up_all(AxisType test_axis) override;8384// update gains for the rate d down tune type85void updating_rate_d_down_all(AxisType test_axis) override {};8687// update gains for the rate ff up tune type88void updating_rate_ff_up_all(AxisType test_axis) override;8990// update gains for the angle p up tune type91void updating_angle_p_up_all(AxisType test_axis) override;9293// update gains for the angle p down tune type94void updating_angle_p_down_all(AxisType test_axis) override {};9596// update gains for the max gain tune type97void updating_max_gains_all(AxisType test_axis) override;9899// set gains post tune for the tune type100void set_gains_post_tune(AxisType test_axis) override;101102// reverse direction for twitch test103bool twitch_reverse_direction() override { return positive_direction; }104105#if HAL_LOGGING_ENABLED106// methods to log autotune summary data107void Log_AutoTune() override;108void Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel);109110// methods to log autotune time history results for command, angular rate, and attitude.111void Log_AutoTuneDetails() override;112void Log_Write_AutoTuneDetails(float motor_cmd, float tgt_rate_rads, float rate_rads, float tgt_ang_rad, float ang_rad);113114// methods to log autotune frequency response results115void Log_AutoTuneSweep() override;116void Log_Write_AutoTuneSweep(float freq_mtr, float gain_mtr, float phase_mtr, float freq_tgt, float gain_tgt, float phase_tgt);117#endif118119// send intermittent updates to user on status of tune120void do_gcs_announcements() override;121122// send post test updates to user123void do_post_test_gcs_announcements() override;124125// report final gains for a given axis to GCS126void report_final_gains(AxisType test_axis) const override;127128// set the tuning test sequence129void set_tune_sequence() override;130131// get_axis_bitmask accessor132uint8_t get_axis_bitmask() const override { return axis_bitmask; }133134// get_testing_step_timeout_ms accessor135uint32_t get_testing_step_timeout_ms() const override;136137private:138// sweep_info contains information about a specific test's sweep results139struct sweep_info {140float freq;141float gain;142float phase;143};144145// max_gain_data type stores information from the max gain test146struct max_gain_data {147float freq;148float phase;149float gain;150float max_allowed;151};152153// FreqRespCalcType is the type of calculation done for the frequency response154enum FreqRespCalcType {155RATE = 0,156ANGLE = 1,157DRB = 2,158};159160enum FreqRespInput {161MOTOR = 0,162TARGET = 1,163};164165float target_angle_max_rp_cd() const override;166167float target_angle_max_y_cd() const override;168169float target_angle_min_rp_cd() const override;170171float target_angle_min_y_cd() const override;172173float angle_lim_max_rp_cd() const override;174175float angle_lim_neg_rpy_cd() const override;176177// initialize dwell test or angle dwell test variables178void dwell_test_init(float start_frq, float stop_frq, float amplitude, float filt_freq, FreqRespInput freq_resp_input, FreqRespCalcType calc_type, AC_AutoTune_FreqResp::ResponseType resp_type, AC_AutoTune_FreqResp::InputType waveform_input_type);179180// dwell test used to perform frequency dwells for rate gains181void dwell_test_run(sweep_info &test_data);182183// updating_rate_ff_up - adjust FF to ensure the target is reached184// FF is adjusted until rate requested is achieved185void updating_rate_ff_up(float &tune_ff, sweep_info &test_data, float &next_freq);186187// updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not exceed exceed max response gain188void updating_rate_p_up(float &tune_p, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p);189190// updating_rate_d_up - uses maximum allowable gain determined from max_gain test to determine rate d gain where the response gain is at a minimum191void updating_rate_d_up(float &tune_d, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_d);192193// updating_angle_p_up - determines maximum angle p gain for pitch and roll194void updating_angle_p_up(float &tune_p, sweep_info &test_data, float &next_freq);195196// updating_max_gains: use dwells at increasing frequency to determine gain at which instability will occur197void updating_max_gains(sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p, max_gain_data &max_gain_d, float &tune_p, float &tune_d);198199// freq_search_for_phase: general search strategy for specified phase. interpolation done once specified phase has been bounded.200bool freq_search_for_phase(sweep_info test, float desired_phase, float freq_incr, sweep_info &est_data, float &new_freq);201202// reset the max_gains update gain variables203void reset_maxgains_update_gain_variables();204205// reset the sweep variables206void reset_sweep_variables();207208// exceeded_freq_range - ensures tuning remains inside frequency range209bool exceeded_freq_range(float frequency);210211// report gain formatting helper212void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const;213214// define input type as Dwell or Sweep. Used through entire class215AC_AutoTune_FreqResp::InputType input_type;216217sweep_info curr_data; // frequency response test results218float next_test_freq; // next test frequency for next test cycle setup219220// max gain data for rate p tuning221max_gain_data max_rate_p;222// max gain data for rate d tuning223max_gain_data max_rate_d;224225// updating max gain variables226// flag for finding maximum p gain227bool found_max_p;228// flag for finding maximum d gain229bool found_max_d;230231// updating angle P up variables232float phase_max; // track the maximum phase and freq233float freq_max;234float sp_prev_gain; // previous gain235bool found_max_gain_freq; // flag for finding max gain frequency236bool found_peak; // flag for finding the peak of the gain response237238// updating rate D up239float rd_prev_gain; // previous gain240241// freq search for phase242sweep_info prev_test; // data from previous dwell243244// Dwell Test variables245AC_AutoTune_FreqResp::InputType test_input_type;246FreqRespCalcType test_calc_type;247FreqRespInput test_freq_resp_input;248uint8_t num_dwell_cycles;249float test_start_freq;250float tgt_attitude;251252float pre_calc_cycles; // number of cycles to complete before running frequency response calculations253float command_out; // test axis command output254float filt_target_rate; // filtered target rate255float dwell_start_time_ms; // start time in ms of dwell test256257sweep_info curr_test;258sweep_info curr_test_mtr;259sweep_info curr_test_tgt;260261Vector3f start_angles; // aircraft attitude at the start of test262uint32_t settle_time; // time in ms for allowing aircraft to stabilize before initiating test263264// variables from dwell test265LowPassFilterVector2f filt_att_fdbk_from_velxy_cd;266LowPassFilterFloat filt_command_reading; // filtered command reading to keep oscillation centered267LowPassFilterFloat filt_gyro_reading; // filtered gyro reading to keep oscillation centered268LowPassFilterFloat filt_tgt_rate_reading; // filtered target rate reading to keep oscillation centered269270// trim variables for determining trim state prior to test starting271float trim_yaw_tgt_reading_cd; // trim target yaw reading before starting test272float trim_yaw_heading_reading_cd; // trim heading reading before starting test273274LowPassFilterFloat command_filt; // filtered command - filtering intended to remove noise275LowPassFilterFloat target_rate_filt; // filtered target rate in radians/second - filtering intended to remove noise276277// sweep_data tracks the overall characteristics in the response to the frequency sweep278struct sweep_data {279sweep_info maxgain;280sweep_info ph180;281sweep_info ph270;282uint8_t progress; // set based on phase of frequency response. 0 - start; 1 - reached 180 deg; 2 - reached 270 deg;283};284sweep_data sweep_mtr;285sweep_data sweep_tgt;286bool sweep_complete;287288// fix the frequency sweep time to 23 seconds289const float sweep_time_ms = 23000;290291// parameters292AP_Int8 axis_bitmask; // axes to be tuned293AP_Int8 seq_bitmask; // tuning sequence bitmask294AP_Float min_sweep_freq; // minimum sweep frequency295AP_Float max_sweep_freq; // maximum sweep frequency296AP_Float max_resp_gain; // maximum response gain297AP_Float vel_hold_gain; // gain for velocity hold298AP_Float accel_max; // maximum autotune angular acceleration299AP_Float rate_max; // maximum autotune angular rate300301// freqresp object for the frequency response tests302AC_AutoTune_FreqResp freqresp_mtr; // frequency response of output to motor mixer input303AC_AutoTune_FreqResp freqresp_tgt; // frequency response of output to target input304305// allow tracking of cycles complete for frequency response object306bool cycle_complete_tgt;307bool cycle_complete_mtr;308309Chirp chirp_input;310};311312#endif // AC_AUTOTUNE_ENABLED313314315