mirror of https://github.com/ArduPilot/ardupilot
AC_AutoTune: restrict scoping of LEVEL_ISSUE enum
This gives us tighter type-checking and scoping
This commit is contained in:
parent
a451380d61
commit
87d05d843e
|
@ -226,19 +226,19 @@ bool AC_AutoTune::start(void)
|
|||
const char *AC_AutoTune::level_issue_string() const
|
||||
{
|
||||
switch (level_problem.issue) {
|
||||
case LEVEL_ISSUE_NONE:
|
||||
case LevelIssue::NONE:
|
||||
return "None";
|
||||
case LEVEL_ISSUE_ANGLE_ROLL:
|
||||
case LevelIssue::ANGLE_ROLL:
|
||||
return "Angle(R)";
|
||||
case LEVEL_ISSUE_ANGLE_PITCH:
|
||||
case LevelIssue::ANGLE_PITCH:
|
||||
return "Angle(P)";
|
||||
case LEVEL_ISSUE_ANGLE_YAW:
|
||||
case LevelIssue::ANGLE_YAW:
|
||||
return "Angle(Y)";
|
||||
case LEVEL_ISSUE_RATE_ROLL:
|
||||
case LevelIssue::RATE_ROLL:
|
||||
return "Rate(R)";
|
||||
case LEVEL_ISSUE_RATE_PITCH:
|
||||
case LevelIssue::RATE_PITCH:
|
||||
return "Rate(P)";
|
||||
case LEVEL_ISSUE_RATE_YAW:
|
||||
case LevelIssue::RATE_YAW:
|
||||
return "Rate(Y)";
|
||||
}
|
||||
return "Bug";
|
||||
|
@ -414,7 +414,7 @@ void AC_AutoTune::run()
|
|||
|
||||
}
|
||||
|
||||
bool AC_AutoTune::check_level(const LEVEL_ISSUE issue, const float current, const float maximum)
|
||||
bool AC_AutoTune::check_level(const LevelIssue issue, const float current, const float maximum)
|
||||
{
|
||||
if (current > maximum) {
|
||||
level_problem.current = current;
|
||||
|
@ -435,33 +435,33 @@ bool AC_AutoTune::currently_level()
|
|||
threshold_mul *= 2;
|
||||
}
|
||||
|
||||
if (!check_level(LEVEL_ISSUE_ANGLE_ROLL,
|
||||
if (!check_level(LevelIssue::ANGLE_ROLL,
|
||||
abs(ahrs_view->roll_sensor - roll_cd),
|
||||
threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!check_level(LEVEL_ISSUE_ANGLE_PITCH,
|
||||
if (!check_level(LevelIssue::ANGLE_PITCH,
|
||||
abs(ahrs_view->pitch_sensor - pitch_cd),
|
||||
threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
|
||||
return false;
|
||||
}
|
||||
if (!check_level(LEVEL_ISSUE_ANGLE_YAW,
|
||||
if (!check_level(LevelIssue::ANGLE_YAW,
|
||||
fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)),
|
||||
threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
|
||||
return false;
|
||||
}
|
||||
if (!check_level(LEVEL_ISSUE_RATE_ROLL,
|
||||
if (!check_level(LevelIssue::RATE_ROLL,
|
||||
(ToDeg(ahrs_view->get_gyro().x) * 100.0f),
|
||||
threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD)) {
|
||||
return false;
|
||||
}
|
||||
if (!check_level(LEVEL_ISSUE_RATE_PITCH,
|
||||
if (!check_level(LevelIssue::RATE_PITCH,
|
||||
(ToDeg(ahrs_view->get_gyro().y) * 100.0f),
|
||||
threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD)) {
|
||||
return false;
|
||||
}
|
||||
if (!check_level(LEVEL_ISSUE_RATE_YAW,
|
||||
if (!check_level(LevelIssue::RATE_YAW,
|
||||
(ToDeg(ahrs_view->get_gyro().z) * 100.0f),
|
||||
threshold_mul*AUTOTUNE_LEVEL_RATE_Y_CD)) {
|
||||
return false;
|
||||
|
|
|
@ -114,16 +114,16 @@ private:
|
|||
void announce_state_to_gcs();
|
||||
void do_gcs_announcements();
|
||||
|
||||
enum LEVEL_ISSUE {
|
||||
LEVEL_ISSUE_NONE,
|
||||
LEVEL_ISSUE_ANGLE_ROLL,
|
||||
LEVEL_ISSUE_ANGLE_PITCH,
|
||||
LEVEL_ISSUE_ANGLE_YAW,
|
||||
LEVEL_ISSUE_RATE_ROLL,
|
||||
LEVEL_ISSUE_RATE_PITCH,
|
||||
LEVEL_ISSUE_RATE_YAW,
|
||||
enum struct LevelIssue {
|
||||
NONE,
|
||||
ANGLE_ROLL,
|
||||
ANGLE_PITCH,
|
||||
ANGLE_YAW,
|
||||
RATE_ROLL,
|
||||
RATE_PITCH,
|
||||
RATE_YAW,
|
||||
};
|
||||
bool check_level(const enum LEVEL_ISSUE issue, const float current, const float maximum);
|
||||
bool check_level(const enum LevelIssue issue, const float current, const float maximum);
|
||||
bool currently_level();
|
||||
|
||||
// autotune modes (high level states)
|
||||
|
@ -216,7 +216,7 @@ private:
|
|||
float roll_cd, pitch_cd;
|
||||
|
||||
struct {
|
||||
LEVEL_ISSUE issue{LEVEL_ISSUE_NONE};
|
||||
LevelIssue issue{LevelIssue::NONE};
|
||||
float maximum;
|
||||
float current;
|
||||
} level_problem;
|
||||
|
|
Loading…
Reference in New Issue