forked from Archive/PX4-Autopilot
Commander: Improve preflight check experience
* Loosen thresholds for gyro consistency check until temperature compensated units are the norm * Cut down string lengths so they make it through the MAVLink transport as a whole
This commit is contained in:
parent
4dc96e3ea1
commit
fff35fe34b
|
@ -176,14 +176,14 @@ static bool imuConsistencyCheck(orb_advert_t *mavlink_log_pub, bool checkAcc, bo
|
|||
if (checkAcc) {
|
||||
if (sensors.accel_inconsistency_m_s_s > test_limit) {
|
||||
if (report_status) {
|
||||
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: ACCEL SENSORS INCONSISTENT - CHECK CALIBRATION");
|
||||
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: ACCELS INCONSISTENT - CHECK CAL");
|
||||
}
|
||||
success = false;
|
||||
goto out;
|
||||
|
||||
} else if (sensors.accel_inconsistency_m_s_s > test_limit * 0.5f) {
|
||||
if (report_status) {
|
||||
mavlink_log_info(mavlink_log_pub, "PREFLIGHT ADVICE: ACCEL SENSORS INCONSISTENT - CHECK CALIBRATION");
|
||||
mavlink_log_info(mavlink_log_pub, "PREFLIGHT ADVICE: ACCELS INCONSISTENT - CHECK CAL");
|
||||
|
||||
}
|
||||
}
|
||||
|
@ -193,14 +193,14 @@ static bool imuConsistencyCheck(orb_advert_t *mavlink_log_pub, bool checkAcc, bo
|
|||
if (checkGyro) {
|
||||
if (sensors.gyro_inconsistency_rad_s > test_limit) {
|
||||
if (report_status) {
|
||||
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: GYRO SENSORS INCONSISTENT - CHECK CALIBRATION");
|
||||
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: GYROS INCONSISTENT - CHECK CAL");
|
||||
}
|
||||
success = false;
|
||||
goto out;
|
||||
|
||||
} else if (sensors.gyro_inconsistency_rad_s > test_limit * 0.5f) {
|
||||
if (report_status) {
|
||||
mavlink_log_info(mavlink_log_pub, "PREFLIGHT ADVICE: GYRO SENSORS INCONSISTENT - CHECK CALIBRATION");
|
||||
mavlink_log_info(mavlink_log_pub, "PREFLIGHT ADVICE: GYROS INCONSISTENT - CHECK CAL");
|
||||
|
||||
}
|
||||
}
|
||||
|
|
|
@ -581,4 +581,4 @@ PARAM_DEFINE_FLOAT(COM_ARM_IMU_ACC, 0.7f);
|
|||
* @decimal 3
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_ARM_IMU_GYR, 0.09f);
|
||||
PARAM_DEFINE_FLOAT(COM_ARM_IMU_GYR, 0.15f);
|
||||
|
|
Loading…
Reference in New Issue