2020-10-19 23:51:05 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
/*
2021-01-17 22:28:20 -04:00
support for autotune of helicopters
2020-10-19 23:51:05 -03:00
*/
# pragma once
2023-12-07 20:03:15 -04:00
# include "AC_AutoTune_config.h"
# if AC_AUTOTUNE_ENABLED
2020-10-19 23:51:05 -03:00
# include "AC_AutoTune.h"
2022-03-07 01:23:41 -04:00
# include <AP_Math/chirp.h>
2022-11-08 00:23:09 -04:00
# include <GCS_MAVLink/GCS.h>
2020-10-19 23:51:05 -03:00
2022-11-08 06:10:56 -04:00
# include <AP_Scheduler/AP_Scheduler.h>
2020-10-19 23:51:05 -03:00
class AC_AutoTune_Heli : public AC_AutoTune
{
public :
// constructor
2021-01-18 00:16:08 -04:00
AC_AutoTune_Heli ( ) ;
2020-10-19 23:51:05 -03:00
// save gained, called on disarm
void save_tuning_gains ( ) override ;
2021-01-18 00:16:08 -04:00
// var_info for holding Parameter information
static const struct AP_Param : : GroupInfo var_info [ ] ;
2020-10-19 23:51:05 -03:00
protected :
2021-01-17 22:28:20 -04:00
2021-12-22 10:45:38 -04:00
//
// methods to load and save gains
//
// backup original gains and prepare for start of tuning
void backup_gains_and_initialise ( ) override ;
2021-01-17 22:28:20 -04:00
2022-03-31 17:52:40 -03:00
// load gains
2024-05-19 23:36:38 -03:00
void 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 ) ;
2022-03-31 17:52:40 -03:00
2021-12-22 10:45:38 -04:00
// switch to use original gains
void load_orig_gains ( ) override ;
2021-01-17 22:28:20 -04:00
2021-12-22 10:45:38 -04:00
// switch to gains found by last successful autotune
void load_tuned_gains ( ) override ;
2021-01-17 22:28:20 -04:00
2021-12-22 10:45:38 -04:00
// load gains used between tests. called during testing mode's update-gains step to set gains ahead of return-to-level step
void load_intra_test_gains ( ) override ;
// load test gains
void load_test_gains ( ) override ;
2021-01-17 22:28:20 -04:00
2023-10-11 04:41:49 -03:00
// reset the test variables for heli
2021-12-22 23:37:31 -04:00
void reset_vehicle_test_variables ( ) override ;
2022-01-07 14:37:02 -04:00
// reset the update gain variables for heli
void reset_update_gain_variables ( ) override ;
2021-12-06 00:27:42 -04:00
// initializes test
2020-10-19 23:51:05 -03:00
void test_init ( ) override ;
2021-12-06 00:27:42 -04:00
// runs test
2020-10-19 23:51:05 -03:00
void test_run ( AxisType test_axis , const float dir_sign ) override ;
2021-01-17 22:28:20 -04:00
// update gains for the rate p up tune type
2020-10-19 23:51:05 -03:00
void updating_rate_p_up_all ( AxisType test_axis ) override ;
2021-01-17 22:28:20 -04:00
// update gains for the rate d up tune type
2020-10-19 23:51:05 -03:00
void updating_rate_d_up_all ( AxisType test_axis ) override ;
2021-01-17 22:28:20 -04:00
// update gains for the rate d down tune type
2020-10-19 23:51:05 -03:00
void updating_rate_d_down_all ( AxisType test_axis ) override { } ;
2021-01-17 22:28:20 -04:00
// update gains for the rate ff up tune type
2020-10-19 23:51:05 -03:00
void updating_rate_ff_up_all ( AxisType test_axis ) override ;
2021-01-17 22:28:20 -04:00
// update gains for the angle p up tune type
2020-10-19 23:51:05 -03:00
void updating_angle_p_up_all ( AxisType test_axis ) override ;
2021-01-17 22:28:20 -04:00
// update gains for the angle p down tune type
2020-10-19 23:51:05 -03:00
void updating_angle_p_down_all ( AxisType test_axis ) override { } ;
2021-01-17 22:28:20 -04:00
// update gains for the max gain tune type
2020-10-19 23:51:05 -03:00
void updating_max_gains_all ( AxisType test_axis ) override ;
2021-12-27 00:53:50 -04:00
// set gains post tune for the tune type
void set_gains_post_tune ( AxisType test_axis ) override ;
2021-01-17 22:28:20 -04:00
2021-01-18 00:16:08 -04:00
// reverse direction for twitch test
bool twitch_reverse_direction ( ) override { return positive_direction ; }
2023-07-13 21:58:04 -03:00
# if HAL_LOGGING_ENABLED
2021-12-06 00:27:42 -04:00
// methods to log autotune summary data
2020-10-19 23:51:05 -03:00
void Log_AutoTune ( ) override ;
2021-01-18 00:16:08 -04:00
void Log_Write_AutoTune ( uint8_t _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 ) ;
2021-12-06 00:27:42 -04:00
// methods to log autotune time history results for command, angular rate, and attitude.
void Log_AutoTuneDetails ( ) override ;
2021-01-18 00:16:08 -04:00
void Log_Write_AutoTuneDetails ( float motor_cmd , float tgt_rate_rads , float rate_rads , float tgt_ang_rad , float ang_rad ) ;
2021-12-06 00:27:42 -04:00
// methods to log autotune frequency response results
void Log_AutoTuneSweep ( ) override ;
2024-04-07 00:55:51 -03:00
void Log_Write_AutoTuneSweep ( float freq_mtr , float gain_mtr , float phase_mtr , float freq_tgt , float gain_tgt , float phase_tgt ) ;
2023-07-13 21:58:04 -03:00
# endif
2021-12-06 00:27:42 -04:00
2023-10-11 04:41:49 -03:00
// send intermittent updates to user on status of tune
2021-01-17 22:28:20 -04:00
void do_gcs_announcements ( ) override ;
2020-10-19 23:51:05 -03:00
2022-01-07 14:37:02 -04:00
// send post test updates to user
void do_post_test_gcs_announcements ( ) override ;
2022-02-04 19:30:10 -04:00
// report final gains for a given axis to GCS
void report_final_gains ( AxisType test_axis ) const override ;
2021-12-06 00:27:42 -04:00
// set the tuning test sequence
2021-01-18 00:16:08 -04:00
void set_tune_sequence ( ) override ;
2021-12-27 00:53:50 -04:00
// get_axis_bitmask accessor
uint8_t get_axis_bitmask ( ) const override { return axis_bitmask ; }
2021-01-18 00:16:08 -04:00
2021-12-28 00:23:19 -04:00
// get_testing_step_timeout_ms accessor
uint32_t get_testing_step_timeout_ms ( ) const override ;
2020-10-19 23:51:05 -03:00
private :
2024-04-20 11:36:24 -03:00
// sweep_info contains information about a specific test's sweep results
struct sweep_info {
float freq ;
float gain ;
float phase ;
} ;
2021-12-13 00:02:40 -04:00
// max_gain_data type stores information from the max gain test
struct max_gain_data {
float freq ;
float phase ;
float gain ;
float max_allowed ;
} ;
2024-04-11 00:30:36 -03:00
// FreqRespCalcType is the type of calculation done for the frequency response
enum FreqRespCalcType {
2022-03-05 23:16:50 -04:00
RATE = 0 ,
ANGLE = 1 ,
2022-05-08 00:28:50 -03:00
DRB = 2 ,
2022-03-05 23:16:50 -04:00
} ;
2024-04-11 00:30:36 -03:00
enum FreqRespInput {
MOTOR = 0 ,
TARGET = 1 ,
} ;
2024-02-29 02:42:39 -04:00
float target_angle_max_rp_cd ( ) const override ;
float target_angle_max_y_cd ( ) const override ;
float target_angle_min_rp_cd ( ) const override ;
float target_angle_min_y_cd ( ) const override ;
float angle_lim_max_rp_cd ( ) const override ;
float angle_lim_neg_rpy_cd ( ) const override ;
2022-03-05 23:16:50 -04:00
// initialize dwell test or angle dwell test variables
2024-05-19 23:36:38 -03:00
void 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 ) ;
2022-03-05 23:16:50 -04:00
2021-12-13 00:02:40 -04:00
// dwell test used to perform frequency dwells for rate gains
2024-04-13 02:04:33 -03:00
void dwell_test_run ( sweep_info & test_data ) ;
2021-12-13 00:02:40 -04:00
2020-10-19 23:51:05 -03:00
// updating_rate_ff_up - adjust FF to ensure the target is reached
2023-10-11 04:41:49 -03:00
// FF is adjusted until rate requested is achieved
2024-04-12 00:21:16 -03:00
void updating_rate_ff_up ( float & tune_ff , sweep_info & test_data , float & next_freq ) ;
2021-12-06 00:27:42 -04:00
// 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 gain
2024-04-12 02:09:33 -03:00
void updating_rate_p_up ( float & tune_p , sweep_info & test_data , float & next_freq , max_gain_data & max_gain_p ) ;
2021-12-06 00:27:42 -04:00
// 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 minimum
2024-04-12 02:09:33 -03:00
void updating_rate_d_up ( float & tune_d , sweep_info & test_data , float & next_freq , max_gain_data & max_gain_d ) ;
2021-12-06 00:27:42 -04:00
// updating_angle_p_up - determines maximum angle p gain for pitch and roll
2024-04-12 23:26:56 -03:00
void updating_angle_p_up ( float & tune_p , sweep_info & test_data , float & next_freq ) ;
2021-12-06 00:27:42 -04:00
2020-10-19 23:51:05 -03:00
// updating_max_gains: use dwells at increasing frequency to determine gain at which instability will occur
2024-04-13 02:04:33 -03:00
void 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 ) ;
2020-10-19 23:51:05 -03:00
2024-04-16 00:18:32 -03:00
// freq_search_for_phase: general search strategy for specified phase. interpolation done once specified phase has been bounded.
bool freq_search_for_phase ( sweep_info test , float desired_phase , float freq_incr , sweep_info & est_data , float & new_freq ) ;
2022-01-16 19:13:59 -04:00
// reset the max_gains update gain variables
void reset_maxgains_update_gain_variables ( ) ;
// reset the sweep variables
void reset_sweep_variables ( ) ;
2022-01-21 14:44:36 -04:00
// exceeded_freq_range - ensures tuning remains inside frequency range
bool exceeded_freq_range ( float frequency ) ;
2021-12-06 00:27:42 -04:00
2023-10-11 04:41:49 -03:00
// report gain formatting helper
2022-02-04 19:30:10 -04:00
void 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 ;
2024-04-11 00:30:36 -03:00
// define input type as Dwell or Sweep. Used through entire class
AC_AutoTune_FreqResp : : InputType input_type ;
2024-04-12 00:21:16 -03:00
sweep_info curr_data ; // frequency response test results
float next_test_freq ; // next test frequency for next test cycle setup
// max gain data for rate p tuning
max_gain_data max_rate_p ;
// max gain data for rate d tuning
max_gain_data max_rate_d ;
2021-10-06 00:50:02 -03:00
// updating max gain variables
2021-12-06 00:27:42 -04:00
// flag for finding maximum p gain
2021-10-06 00:50:02 -03:00
bool found_max_p ;
2021-12-06 00:27:42 -04:00
// flag for finding maximum d gain
2021-10-06 00:50:02 -03:00
bool found_max_d ;
// updating angle P up variables
2024-04-16 00:18:32 -03:00
float phase_max ; // track the maximum phase and freq
2024-04-12 23:26:56 -03:00
float freq_max ;
2024-04-16 00:18:32 -03:00
float sp_prev_gain ; // previous gain
bool found_max_gain_freq ; // flag for finding max gain frequency
bool found_peak ; // flag for finding the peak of the gain response
2021-10-06 00:50:02 -03:00
// updating rate D up
2024-04-16 00:18:32 -03:00
float rd_prev_gain ; // previous gain
// freq search for phase
sweep_info prev_test ; // data from previous dwell
2021-01-18 00:16:08 -04:00
2024-04-11 00:30:36 -03:00
// Dwell Test variables
AC_AutoTune_FreqResp : : InputType test_input_type ;
FreqRespCalcType test_calc_type ;
FreqRespInput test_freq_resp_input ;
uint8_t num_dwell_cycles ;
float test_start_freq ;
2024-05-19 23:36:38 -03:00
float tgt_attitude ;
2024-04-11 00:30:36 -03:00
2024-04-12 00:21:16 -03:00
float pre_calc_cycles ; // number of cycles to complete before running frequency response calculations
2021-12-13 00:02:40 -04:00
float command_out ; // test axis command output
float filt_target_rate ; // filtered target rate
float dwell_start_time_ms ; // start time in ms of dwell test
2022-02-08 19:31:51 -04:00
sweep_info curr_test ;
2024-04-07 00:55:51 -03:00
sweep_info curr_test_mtr ;
sweep_info curr_test_tgt ;
2022-02-08 19:31:51 -04:00
2021-12-13 00:02:40 -04:00
Vector3f start_angles ; // aircraft attitude at the start of test
uint32_t settle_time ; // time in ms for allowing aircraft to stabilize before initiating test
float trim_meas_rate ; // trim measured gyro rate
2022-01-01 23:33:52 -04:00
// variables from dwell test
LowPassFilterVector2f filt_att_fdbk_from_velxy_cd ;
LowPassFilterFloat filt_command_reading ; // filtered command reading to keep oscillation centered
LowPassFilterFloat filt_gyro_reading ; // filtered gyro reading to keep oscillation centered
LowPassFilterFloat filt_tgt_rate_reading ; // filtered target rate reading to keep oscillation centered
// trim variables for determining trim state prior to test starting
2024-07-03 06:34:05 -03:00
float trim_yaw_tgt_reading_cd ; // trim target yaw reading before starting test
float trim_yaw_heading_reading_cd ; // trim heading reading before starting test
2022-01-01 23:33:52 -04:00
LowPassFilterFloat command_filt ; // filtered command - filtering intended to remove noise
LowPassFilterFloat target_rate_filt ; // filtered target rate in radians/second - filtering intended to remove noise
2021-12-13 00:02:40 -04:00
// sweep_data tracks the overall characteristics in the response to the frequency sweep
struct sweep_data {
2022-02-08 19:31:51 -04:00
sweep_info maxgain ;
sweep_info ph180 ;
sweep_info ph270 ;
2021-12-13 00:02:40 -04:00
uint8_t progress ; // set based on phase of frequency response. 0 - start; 1 - reached 180 deg; 2 - reached 270 deg;
} ;
2024-04-07 00:55:51 -03:00
sweep_data sweep_mtr ;
sweep_data sweep_tgt ;
2024-04-12 23:26:56 -03:00
bool sweep_complete ;
2021-12-13 00:02:40 -04:00
2022-03-07 01:23:41 -04:00
// fix the frequency sweep time to 23 seconds
const float sweep_time_ms = 23000 ;
2021-12-27 00:53:50 -04:00
// parameters
AP_Int8 axis_bitmask ; // axes to be tuned
AP_Int8 seq_bitmask ; // tuning sequence bitmask
AP_Float min_sweep_freq ; // minimum sweep frequency
AP_Float max_sweep_freq ; // maximum sweep frequency
AP_Float max_resp_gain ; // maximum response gain
AP_Float vel_hold_gain ; // gain for velocity hold
2024-04-01 00:41:59 -03:00
AP_Float accel_max ; // maximum autotune angular acceleration
AP_Float rate_max ; // maximum autotune angular rate
2021-12-27 00:53:50 -04:00
2022-03-06 20:32:12 -04:00
// freqresp object for the frequency response tests
2024-04-07 00:55:51 -03:00
AC_AutoTune_FreqResp freqresp_mtr ; // frequency response of output to motor mixer input
AC_AutoTune_FreqResp freqresp_tgt ; // frequency response of output to target input
2022-03-07 01:23:41 -04:00
2024-04-08 00:34:47 -03:00
// allow tracking of cycles complete for frequency response object
bool cycle_complete_tgt ;
bool cycle_complete_mtr ;
2022-03-07 01:23:41 -04:00
Chirp chirp_input ;
2020-10-19 23:51:05 -03:00
} ;
2023-12-07 20:03:15 -04:00
# endif // AC_AUTOTUNE_ENABLED