From 5cd0ca851a94d6ef51d0ff2e958587d73baf400e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 28 Dec 2015 20:36:11 -0800 Subject: [PATCH] Copter: check if accel cal requires reboot --- ArduCopter/arming_checks.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/ArduCopter/arming_checks.cpp b/ArduCopter/arming_checks.cpp index 7a34360a9f..f1462b98c0 100644 --- a/ArduCopter/arming_checks.cpp +++ b/ArduCopter/arming_checks.cpp @@ -184,6 +184,14 @@ bool Copter::pre_arm_checks(bool display_failure) return false; } + //check if accelerometers have calibrated and require reboot + if (ins.accel_cal_requires_reboot()) { + if (display_failure) { + gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accelerometers calibrated requires reboot"); + } + return false; + } + // check all accelerometers point in roughly same direction if (ins.get_accel_count() > 1) { const Vector3f &prime_accel_vec = ins.get_accel(); @@ -482,6 +490,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs) // check accels and gyro are healthy if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) { + //check if accelerometers have calibrated and require reboot + if (ins.accel_cal_requires_reboot()) { + if (display_failure) { + gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Accelerometers calibrated requires reboot"); + } + return false; + } + if (!ins.get_accel_health_all()) { if (display_failure) { gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Accelerometers not healthy");