mirror of https://github.com/ArduPilot/ardupilot
AC_AutoTune: make incrementing the tune type a function
This commit is contained in:
parent
24603f3cf1
commit
c817e92ada
|
@ -593,13 +593,11 @@ void AC_AutoTune::control_attitude()
|
|||
}
|
||||
|
||||
// increment the tune type to the next one in tune sequence
|
||||
tune_seq_curr++;
|
||||
tune_type = tune_seq[tune_seq_curr];
|
||||
next_tune_type(tune_type, false);
|
||||
|
||||
if (tune_type == TUNE_COMPLETE) {
|
||||
// we've reached the end of a D-up-down PI-up-down tune type cycle
|
||||
tune_seq_curr = 0;
|
||||
tune_type = tune_seq[tune_seq_curr];
|
||||
next_tune_type(tune_type, true);
|
||||
|
||||
// advance to the next axis
|
||||
bool complete = false;
|
||||
|
@ -675,12 +673,8 @@ void AC_AutoTune::backup_gains_and_initialise()
|
|||
// no axes are complete
|
||||
axes_completed = 0;
|
||||
|
||||
// set the tune sequence
|
||||
set_tune_sequence();
|
||||
|
||||
// start at the beginning of tune sequence
|
||||
tune_seq_curr = 0;
|
||||
tune_type = tune_seq[tune_seq_curr];
|
||||
next_tune_type(tune_type, true);
|
||||
|
||||
positive_direction = false;
|
||||
step = WAITING_FOR_LEVEL;
|
||||
|
@ -848,3 +842,16 @@ void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out,
|
|||
|
||||
yaw_cd_out = target_yaw_cd;
|
||||
}
|
||||
|
||||
// get the next tune type
|
||||
void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset)
|
||||
{
|
||||
if (reset) {
|
||||
set_tune_sequence();
|
||||
tune_seq_curr = 0;
|
||||
} else {
|
||||
tune_seq_curr++;
|
||||
}
|
||||
curr_tune_type = tune_seq[tune_seq_curr];
|
||||
}
|
||||
|
||||
|
|
|
@ -213,6 +213,12 @@ protected:
|
|||
TuneType tune_seq[6]; // holds sequence of tune_types to be performed
|
||||
uint8_t tune_seq_curr; // current tune sequence step
|
||||
|
||||
// get the next tune type
|
||||
void next_tune_type(TuneType &curr_tune_type, bool reset);
|
||||
|
||||
// Sets customizable tune sequence for the vehicle
|
||||
virtual void set_tune_sequence() = 0;
|
||||
|
||||
// parameters
|
||||
AP_Int8 axis_bitmask; // axes to be tuned
|
||||
AP_Float aggressiveness; // aircraft response aggressiveness to be tuned
|
||||
|
@ -316,9 +322,6 @@ private:
|
|||
FAILED = 3, // tuning has failed, user is flying on original gains
|
||||
};
|
||||
|
||||
// Sets customizable tune sequence for the vehicle
|
||||
virtual void set_tune_sequence() = 0;
|
||||
|
||||
// type of gains to load
|
||||
enum GainType {
|
||||
GAIN_ORIGINAL = 0,
|
||||
|
|
|
@ -105,6 +105,15 @@ protected:
|
|||
void 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);
|
||||
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
|
||||
|
||||
void set_tune_sequence() override {
|
||||
tune_seq[0] = RD_UP;
|
||||
tune_seq[1] = RD_DOWN;
|
||||
tune_seq[2] = RP_UP;
|
||||
tune_seq[3] = SP_DOWN;
|
||||
tune_seq[4] = SP_UP;
|
||||
tune_seq[5] = TUNE_COMPLETE;
|
||||
}
|
||||
|
||||
private:
|
||||
// twitch test functions for multicopter
|
||||
void twitch_test_init();
|
||||
|
@ -137,13 +146,4 @@ private:
|
|||
// P is increased until we achieve our target within a reasonable time
|
||||
void 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);
|
||||
|
||||
void set_tune_sequence() override {
|
||||
tune_seq[0] = RD_UP;
|
||||
tune_seq[1] = RD_DOWN;
|
||||
tune_seq[2] = RP_UP;
|
||||
tune_seq[3] = SP_DOWN;
|
||||
tune_seq[4] = SP_UP;
|
||||
tune_seq[5] = TUNE_COMPLETE;
|
||||
}
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue