mirror of https://github.com/ArduPilot/ardupilot
Rover: add ReportOnly option to FS_EKF_ACTION
This commit is contained in:
parent
a730e47563
commit
5d3dd5a8b8
|
@ -158,9 +158,9 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
// @Param: FS_EKF_ACTION
|
||||
// @DisplayName: EKF Failsafe Action
|
||||
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
|
||||
// @Values: 0:Disabled,1:Hold
|
||||
// @Values: 0:Disabled,1:Hold,2:ReportOnly
|
||||
// @User: Advanced
|
||||
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", 1),
|
||||
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EFK_HOLD),
|
||||
|
||||
// @Param: FS_EKF_THRESH
|
||||
// @DisplayName: EKF failsafe variance threshold
|
||||
|
|
|
@ -85,7 +85,8 @@ enum fs_crash_action {
|
|||
|
||||
enum fs_ekf_action {
|
||||
FS_EKF_DISABLE = 0,
|
||||
FS_EFK_HOLD = 1
|
||||
FS_EFK_HOLD = 1,
|
||||
FS_EFK_REPORT_ONLY = 2,
|
||||
};
|
||||
|
||||
#define DISTANCE_HOME_MINCHANGE 0.5f // minimum distance to adjust home location
|
||||
|
|
|
@ -163,6 +163,8 @@ void Rover::failsafe_ekf_event()
|
|||
case FS_EKF_DISABLE:
|
||||
// do nothing
|
||||
return;
|
||||
case FS_EFK_REPORT_ONLY:
|
||||
break;
|
||||
case FS_EFK_HOLD:
|
||||
default:
|
||||
set_mode(mode_hold, ModeReason::EKF_FAILSAFE);
|
||||
|
|
Loading…
Reference in New Issue