From 01e5ae6e5c6359c1bad33901cfb268267ae775e7 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Mon, 7 Apr 2014 11:18:54 +0900
Subject: [PATCH] Copter: integrate parachute alt_min units change

---
 ArduCopter/crash_check.pde | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/ArduCopter/crash_check.pde b/ArduCopter/crash_check.pde
index 3cf1cc486..eaddb8d6b 100644
--- a/ArduCopter/crash_check.pde
+++ b/ArduCopter/crash_check.pde
@@ -110,7 +110,7 @@ void parachute_check()
     }
 
     // ensure the first control_loss event is from above the min altitude
-    if (control_loss_count == 0 && parachute.alt_min_cm() != 0 && baro_alt < parachute.alt_min_cm()) {
+    if (control_loss_count == 0 && parachute.alt_min() != 0 && (baro_alt < (uint32_t)parachute.alt_min() * 100)) {
         return;
     }
 
@@ -174,7 +174,7 @@ static void parachute_release()
 static void parachute_manual_release()
 {
     // do not release if we are landed or below the minimum altitude above home
-    if (ap.land_complete || (parachute.alt_min_cm() != 0 && baro_alt < parachute.alt_min_cm())) {
+    if (ap.land_complete || (parachute.alt_min() != 0 && (baro_alt < (uint32_t)parachute.alt_min() * 100))) {
         // warn user of reason for failure
         gcs_send_text_P(SEVERITY_HIGH,PSTR("Parachute: Too Low"));
         // log an error in the dataflash
@@ -186,4 +186,4 @@ static void parachute_manual_release()
     parachute_release();
 }
 
-#endif // PARACHUTE == ENABLED
\ No newline at end of file
+#endif // PARACHUTE == ENABLED
-- 
GitLab