Skip to content

Commit

Permalink
Copter: Autotune: Small changes for clarity
Browse files Browse the repository at this point in the history
squash clean up
  • Loading branch information
lthall committed Feb 19, 2024
1 parent 51e15a5 commit 0157658
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 16 deletions.
18 changes: 9 additions & 9 deletions libraries/AC_AutoTune/AC_AutoTune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,18 +10,18 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
# define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg)
# define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec)
# define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg)
# define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec)
#else
# define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level
# define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch
# define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level
# define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch
#endif
#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw
#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 250 // time we require the aircraft to be level before starting next test
#define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level
#define AUTOTUNE_LEVEL_WARNING_INTERVAL_MS 5000 // level failure warning messages sent at this interval to users
#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw
#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 250 // time we require the aircraft to be level before starting next test
#define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level
#define AUTOTUNE_LEVEL_WARNING_INTERVAL_MS 5000 // level failure warning messages sent at this interval to users
#define AUTOTUNE_ANGLE_MAX_RLLPIT_SCALE 2.0 / 3.0 // maximum allowable angle during testing, as a fraction of angle_max

AC_AutoTune::AC_AutoTune()
Expand Down
4 changes: 2 additions & 2 deletions libraries/AC_AutoTune/AC_AutoTune.h
Original file line number Diff line number Diff line change
Expand Up @@ -211,8 +211,8 @@ class AC_AutoTune
RD_DOWN = 1, // rate D is being tuned down
RP_UP = 2, // rate P is being tuned up
RFF_UP = 3, // rate FF is being tuned up
SP_UP = 4, // angle P is being tuned up
SP_DOWN = 5, // angle P is being tuned down
SP_DOWN = 4, // angle P is being tuned down
SP_UP = 5, // angle P is being tuned up
MAX_GAINS = 6, // max allowable stable gains are determined
TUNE_CHECK = 7, // frequency sweep with tuned gains
TUNE_COMPLETE = 8 // Reached end of tuning
Expand Down
10 changes: 5 additions & 5 deletions libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@

// roll and pitch axes
#define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target min roll/pitch rate during AUTOTUNE_STEP_TWITCHING step

// yaw axis
#define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
Expand Down Expand Up @@ -516,8 +516,8 @@ void AC_AutoTune_Multi::twitching_test_rate(float rate, float rate_target_max, f
}

// calculate early stopping time based on the time it takes to get to 75%
if (meas_rate_max < rate_target_max * 0.75f) {
// the measurement not reached the 75% threshold yet
if (meas_rate_max < rate_target_max * 0.6321) {
// the measurement not reached the 63.21% threshold yet
step_time_limit_ms = (now - step_start_time_ms) * 3;
step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
}
Expand Down Expand Up @@ -592,8 +592,8 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl
}

// calculate early stopping time based on the time it takes to get to 75%
if (meas_angle_max < angle_target_max * 0.75f) {
// the measurement not reached the 75% threshold yet
if (meas_angle_max < angle_target_max * 0.6321) {
// the measurement not reached the 63.21% threshold yet
step_time_limit_ms = (now - step_start_time_ms) * 3;
step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
}
Expand Down

0 comments on commit 0157658

Please sign in to comment.