diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 1e009c2c60..d0dd641dea 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -160,7 +160,7 @@ const AP_Param::Info Rover::var_info[] = { // @Description: Controls the action that will be taken when an EKF failsafe is invoked // @Values: 0:Disabled,1:Hold,2:ReportOnly // @User: Advanced - GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EFK_HOLD), + GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_HOLD), // @Param: FS_EKF_THRESH // @DisplayName: EKF failsafe variance threshold diff --git a/Rover/defines.h b/Rover/defines.h index 31b4996903..2c53628321 100644 --- a/Rover/defines.h +++ b/Rover/defines.h @@ -85,8 +85,8 @@ enum fs_crash_action { enum fs_ekf_action { FS_EKF_DISABLE = 0, - FS_EFK_HOLD = 1, - FS_EFK_REPORT_ONLY = 2, + FS_EKF_HOLD = 1, + FS_EKF_REPORT_ONLY = 2, }; #define DISTANCE_HOME_MINCHANGE 0.5f // minimum distance to adjust home location diff --git a/Rover/ekf_check.cpp b/Rover/ekf_check.cpp index 38f82dbce9..e89f198a29 100644 --- a/Rover/ekf_check.cpp +++ b/Rover/ekf_check.cpp @@ -163,9 +163,9 @@ void Rover::failsafe_ekf_event() case FS_EKF_DISABLE: // do nothing return; - case FS_EFK_REPORT_ONLY: + case FS_EKF_REPORT_ONLY: break; - case FS_EFK_HOLD: + case FS_EKF_HOLD: default: set_mode(mode_hold, ModeReason::EKF_FAILSAFE); break;