Skip to content

Commit

Permalink
AC_Autotune: Clean up Multi Variables and non functional changes
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Jun 24, 2024
1 parent 9fdf52c commit 185332a
Show file tree
Hide file tree
Showing 4 changed files with 131 additions and 130 deletions.
15 changes: 5 additions & 10 deletions libraries/AC_AutoTune/AC_AutoTune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,9 @@ void AC_AutoTune::send_step_string()
case UPDATE_GAINS:
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Updating Gains");
return;
case ABORT:
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Aborting Test");
return;
case TESTING:
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Testing");
return;
Expand Down Expand Up @@ -340,13 +343,6 @@ void AC_AutoTune::control_attitude()
step_start_time_ms = now;
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;
test_rate_min = 0.0f;
test_angle_max = 0.0f;
test_angle_min = 0.0f;
rotation_rate_filt.reset(0.0f);
rate_max = 0.0f;
load_gains(GAIN_TEST);
} else {
// when waiting for level we use the intra-test gains
Expand All @@ -356,18 +352,15 @@ void AC_AutoTune::control_attitude()
// Initialize test-specific variables
switch (axis) {
case ROLL:
angle_finish = target_angle_max_rp_cd();
start_rate = ToDeg(ahrs_view->get_gyro().x) * 100.0f;
start_angle = ahrs_view->roll_sensor;
break;
case PITCH:
angle_finish = target_angle_max_rp_cd();
start_rate = ToDeg(ahrs_view->get_gyro().y) * 100.0f;
start_angle = ahrs_view->pitch_sensor;
break;
case YAW:
case YAW_D:
angle_finish = target_angle_max_y_cd();
start_rate = ToDeg(ahrs_view->get_gyro().z) * 100.0f;
start_angle = ahrs_view->yaw_sensor;
break;
Expand Down Expand Up @@ -537,7 +530,9 @@ void AC_AutoTune::control_attitude()
}
}
}
FALLTHROUGH;

case ABORT:
if (axis == YAW || axis == YAW_D) {
attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs_view->yaw_sensor, false);
}
Expand Down
21 changes: 7 additions & 14 deletions libraries/AC_AutoTune/AC_AutoTune.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,8 @@ class AC_AutoTune
enum StepType {
WAITING_FOR_LEVEL = 0, // autotune is waiting for vehicle to return to level before beginning the next twitch
TESTING = 1, // autotune has begun a test and is watching the resulting vehicle movement
UPDATE_GAINS = 2 // autotune has completed a test and is updating the gains based on the results
UPDATE_GAINS = 2, // autotune has completed a test and is updating the gains based on the results
ABORT = 3 // load normal gains and return to WAITING_FOR_LEVEL
};

// mini steps performed while in Tuning mode, Testing step
Expand Down Expand Up @@ -259,26 +260,18 @@ class AC_AutoTune
bool positive_direction; // false = tuning in negative direction (i.e. left for roll), true = positive direction (i.e. right for roll)
StepType step; // see StepType for what steps are performed
TuneType tune_type; // see TuneType
bool ignore_next; // true = ignore the next test
bool twitch_first_iter; // true on first iteration of a twitch (used to signal we must step the attitude or rate target)
uint8_t axes_completed; // bitmask of completed axes
float test_rate_min; // the minimum angular rate achieved during TESTING_RATE step-multi only
float test_rate_max; // the maximum angular rate achieved during TESTING_RATE step-multi only
float test_angle_min; // the minimum angle achieved during TESTING_ANGLE step-multi only
float test_angle_max; // the maximum angle achieved during TESTING_ANGLE step-multi only
uint32_t step_start_time_ms; // start time of current tuning step (used for timeout checks)
uint32_t step_time_limit_ms; // time limit of current autotune process
uint32_t level_start_time_ms; // start time of waiting for level
int8_t counter; // counter for tuning gains
float target_rate; // target rate-multi only
float target_angle; // target angle-multi only
float start_rate; // start rate - parent and multi
float start_angle; // start angle
float rate_max; // maximum rate variable - parent and multi
float start_rate; // start rate - parent and multi
float test_accel_max; // maximum acceleration variable
float step_scaler; // scaler to reduce maximum target step - parent and multi
float angle_finish; // Angle that test is aborted- parent and multi

float desired_yaw_cd; // yaw heading during tune - parent and Tradheli
float step_scaler; // scaler to reduce maximum target step - parent and multi

LowPassFilterFloat rotation_rate_filt; // filtered rotation rate in radians/second

Expand All @@ -301,8 +294,8 @@ class AC_AutoTune

// heli specific variables
uint8_t freq_cnt; // dwell test iteration counter
float start_freq; //start freq for dwell test
float stop_freq; //ending freq for dwell test
float start_freq; // start freq for dwell test
float stop_freq; // ending freq for dwell test
bool ff_up_first_iter; // true on first iteration of ff up testing

private:
Expand Down
Loading

0 comments on commit 185332a

Please sign in to comment.