diff --git a/src/modules/commander/PreflightCheck.cpp b/src/modules/commander/PreflightCheck.cpp index 03fcbdfc5d..e180542faf 100644 --- a/src/modules/commander/PreflightCheck.cpp +++ b/src/modules/commander/PreflightCheck.cpp @@ -500,7 +500,7 @@ static bool ekf2Check(orb_advert_t *mavlink_log_pub, bool optional, bool report_ } // check accelerometer delta velocity bias estimates - param_get(param_find("COM_ARM_IMU_AB"), &test_limit); + param_get(param_find("COM_ARM_EKF_AB"), &test_limit); if (fabsf(status.states[13]) > test_limit || fabsf(status.states[14]) > test_limit || fabsf(status.states[15]) > test_limit) { if (report_fail) { mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: EKF HIGH IMU ACCEL BIAS"); @@ -510,7 +510,7 @@ static bool ekf2Check(orb_advert_t *mavlink_log_pub, bool optional, bool report_ } // check gyro delta angle bias estimates - param_get(param_find("COM_ARM_IMU_GB"), &test_limit); + param_get(param_find("COM_ARM_EKF_GB"), &test_limit); if (fabsf(status.states[10]) > test_limit || fabsf(status.states[11]) > test_limit || fabsf(status.states[12]) > test_limit) { if (report_fail) { mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: EKF HIGH IMU GYRO BIAS"); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 0a495d23a8..db3efacd9a 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -527,11 +527,11 @@ PARAM_DEFINE_FLOAT(COM_ARM_EKF_YAW, 0.5f); * @group Commander * @unit m/s * @min 0.001 - * @max 0.004 + * @max 0.01 * @decimal 4 * @increment 0.0005 */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 2.0e-3f); +PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 5.0e-3f); /** * Maximum value of EKF gyro delta angle bias estimate that will allow arming @@ -539,11 +539,11 @@ PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 2.0e-3f); * @group Commander * @unit rad * @min 0.0001 - * @max 0.0007 + * @max 0.0017 * @decimal 5 - * @increment 0.00005 + * @increment 0.0001 */ -PARAM_DEFINE_FLOAT(COM_ARM_EKF_GB, 3.5e-4f); +PARAM_DEFINE_FLOAT(COM_ARM_EKF_GB, 8.7e-4f); /** * Maximum accelerometer inconsistency between IMU units that will allow arming