AC_AutoTune: rename parameter for convention and put testing timeout in subclasses

This commit is contained in:
Bill Geyer 2021-12-27 23:23:19 -05:00 committed by Bill Geyer
parent 66c6a5f877
commit bc2455e285
6 changed files with 33 additions and 13 deletions

View File

@ -356,7 +356,7 @@ void AC_AutoTune::control_attitude()
// initiate variables for next step
step = TESTING;
step_start_time_ms = now;
step_time_limit_ms = AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
step_time_limit_ms = get_testing_step_timeout_ms();
// set gains to their to-be-tested values
twitch_first_iter = true;
test_rate_max = 0.0f;

View File

@ -40,12 +40,6 @@
#define AUTOTUNE_ANNOUNCE_INTERVAL_MS 2000
//#if APM_BUILD_TYPE(APM_BUILD_Heli)
// #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step
//#else
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U // timeout for tuning mode's testing step
//#endif
#define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step
#define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step
#define AUTOTUNE_TARGET_ANGLE_YAW_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step
@ -210,6 +204,9 @@ protected:
// get_axis_bitmask accessor
virtual uint8_t get_axis_bitmask() const = 0;
// get_testing_step_timeout_ms accessor
virtual uint32_t get_testing_step_timeout_ms() const = 0;
// copies of object pointers to make code a bit clearer
AC_AttitudeControl *attitude_control;
AC_PosControl *pos_control;

View File

@ -19,6 +19,8 @@
#include "AC_AutoTune_Heli.h"
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step
#define AUTOTUNE_RD_STEP 0.0005f // minimum increment when increasing/decreasing Rate D term
#define AUTOTUNE_RP_STEP 0.005f // minimum increment when increasing/decreasing Rate P term
#define AUTOTUNE_SP_STEP 0.05f // minimum increment when increasing/decreasing Stab P term
@ -66,26 +68,26 @@ const AP_Param::GroupInfo AC_AutoTune_Heli::var_info[] = {
// @User: Standard
AP_GROUPINFO("SEQ", 2, AC_AutoTune_Heli, seq_bitmask, 5),
// @Param: MIN_FRQ
// @Param: FRQ_MIN
// @DisplayName: AutoTune minimum sweep frequency
// @Description: Defines the start frequency for sweeps and dwells
// @Range: 10 30
// @User: Standard
AP_GROUPINFO("MIN_FRQ", 3, AC_AutoTune_Heli, min_sweep_freq, 10.0f),
AP_GROUPINFO("FRQ_MIN", 3, AC_AutoTune_Heli, min_sweep_freq, 10.0f),
// @Param: MAX_FRQ
// @Param: FRQ_MAX
// @DisplayName: AutoTune maximum sweep frequency
// @Description: Defines the end frequency for sweeps and dwells
// @Range: 50 120
// @User: Standard
AP_GROUPINFO("MAX_FRQ", 4, AC_AutoTune_Heli, max_sweep_freq, 70.0f),
AP_GROUPINFO("FRQ_MAX", 4, AC_AutoTune_Heli, max_sweep_freq, 70.0f),
// @Param: MAX_GN
// @Param: GN_MAX
// @DisplayName: AutoTune maximum response gain
// @Description: Defines the response gain (output/input) to tune
// @Range: 1 2.5
// @User: Standard
AP_GROUPINFO("MAX_GN", 5, AC_AutoTune_Heli, max_resp_gain, 1.4f),
AP_GROUPINFO("GN_MAX", 5, AC_AutoTune_Heli, max_resp_gain, 1.4f),
// @Param: VELXY_P
// @DisplayName: AutoTune velocity xy P gain
@ -2145,3 +2147,9 @@ void AC_AutoTune_Heli::set_tune_sequence()
tune_seq[seq_cnt] = TUNE_COMPLETE;
}
// get_testing_step_timeout_ms accessor
uint32_t AC_AutoTune_Heli::get_testing_step_timeout_ms() const
{
return AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
}

View File

@ -110,6 +110,9 @@ protected:
// get_axis_bitmask accessor
uint8_t get_axis_bitmask() const override { return axis_bitmask; }
// get_testing_step_timeout_ms accessor
uint32_t get_testing_step_timeout_ms() const override;
private:
// max_gain_data type stores information from the max gain test
struct max_gain_data {

View File

@ -36,6 +36,8 @@
*
*/
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U // timeout for tuning mode's testing step
#define AUTOTUNE_RD_STEP 0.05f // minimum increment when increasing/decreasing Rate D term
#define AUTOTUNE_RP_STEP 0.05f // minimum increment when increasing/decreasing Rate P term
#define AUTOTUNE_SP_STEP 0.05f // minimum increment when increasing/decreasing Stab P term
@ -1208,3 +1210,10 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign
break;
}
}
// get_testing_step_timeout_ms accessor
uint32_t AC_AutoTune_Multi::get_testing_step_timeout_ms() const
{
return AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
}

View File

@ -117,6 +117,9 @@ protected:
// get_axis_bitmask accessor
uint8_t get_axis_bitmask() const override { return axis_bitmask; }
// get_testing_step_timeout_ms accessor
uint32_t get_testing_step_timeout_ms() const override;
private:
// twitch test functions for multicopter
void twitch_test_init();