mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 16:03:58 -04:00
Copter: rename ekf_check_thresh to fs_ekf_thresh
This commit is contained in:
parent
125042e1db
commit
4408f01f39
@ -479,12 +479,12 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
|
GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
|
||||||
|
|
||||||
// @Param: EKF_CHECK_THRESH
|
// @Param: FS_EKF_THRESH
|
||||||
// @DisplayName: EKF check compass and velocity variance threshold
|
// @DisplayName: EKF failsafe variance threshold
|
||||||
// @Description: Allows setting the maximum acceptable compass and velocity variance (0 to disable check)
|
// @Description: Allows setting the maximum acceptable compass and velocity variance
|
||||||
// @Values: 0:Disabled, 0.6:Strict, 0.8:Default, 1.0:Relaxed
|
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(ekfcheck_thresh, "EKF_CHECK_THRESH", EKFCHECK_THRESHOLD_DEFAULT),
|
GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// @Group: HS1_
|
// @Group: HS1_
|
||||||
|
@ -120,7 +120,7 @@ public:
|
|||||||
k_param_serial2_baud, // deprecated - remove
|
k_param_serial2_baud, // deprecated - remove
|
||||||
k_param_land_repositioning,
|
k_param_land_repositioning,
|
||||||
k_param_sonar, // sonar object
|
k_param_sonar, // sonar object
|
||||||
k_param_ekfcheck_thresh,
|
k_param_fs_ekf_thresh,
|
||||||
k_param_terrain,
|
k_param_terrain,
|
||||||
k_param_acro_expo,
|
k_param_acro_expo,
|
||||||
k_param_throttle_deadzone,
|
k_param_throttle_deadzone,
|
||||||
@ -414,7 +414,7 @@ public:
|
|||||||
AP_Int8 arming_check;
|
AP_Int8 arming_check;
|
||||||
|
|
||||||
AP_Int8 land_repositioning;
|
AP_Int8 land_repositioning;
|
||||||
AP_Float ekfcheck_thresh;
|
AP_Float fs_ekf_thresh;
|
||||||
AP_Int16 gcs_pid_mask;
|
AP_Int16 gcs_pid_mask;
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
@ -269,9 +269,9 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// EKF Checker
|
// EKF Failsafe
|
||||||
#ifndef EKFCHECK_THRESHOLD_DEFAULT
|
#ifndef FS_EKF_THRESHOLD_DEFAULT
|
||||||
# define EKFCHECK_THRESHOLD_DEFAULT 0.8f // EKF checker's default compass and velocity variance above which the EKF's horizontal position will be considered bad
|
# define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef EKF_ORIGIN_MAX_DIST_M
|
#ifndef EKF_ORIGIN_MAX_DIST_M
|
||||||
|
@ -31,7 +31,7 @@ static struct {
|
|||||||
void Copter::ekf_check()
|
void Copter::ekf_check()
|
||||||
{
|
{
|
||||||
// return immediately if motors are not armed, ekf check is disabled, not using ekf or usb is connected
|
// return immediately if motors are not armed, ekf check is disabled, not using ekf or usb is connected
|
||||||
if (!motors.armed() || ap.usb_connected || (g.ekfcheck_thresh <= 0.0f)) {
|
if (!motors.armed() || ap.usb_connected || (g.fs_ekf_thresh <= 0.0f)) {
|
||||||
ekf_check_state.fail_count = 0;
|
ekf_check_state.fail_count = 0;
|
||||||
ekf_check_state.bad_variance = false;
|
ekf_check_state.bad_variance = false;
|
||||||
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
|
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
|
||||||
@ -87,7 +87,7 @@ bool Copter::ekf_over_threshold()
|
|||||||
{
|
{
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
// return false immediately if disabled
|
// return false immediately if disabled
|
||||||
if (g.ekfcheck_thresh <= 0.0f) {
|
if (g.fs_ekf_thresh <= 0.0f) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -106,7 +106,7 @@ bool Copter::ekf_over_threshold()
|
|||||||
compass_variance = magVar.length();
|
compass_variance = magVar.length();
|
||||||
|
|
||||||
// return true if compass and velocity variance over the threshold
|
// return true if compass and velocity variance over the threshold
|
||||||
return (compass_variance >= g.ekfcheck_thresh && vel_variance >= g.ekfcheck_thresh);
|
return (compass_variance >= g.fs_ekf_thresh && vel_variance >= g.fs_ekf_thresh);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user