Browse Source

Copter: integrate parachute alt_min units change

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
01e5ae6e5c
  1. 6
      ArduCopter/crash_check.pde

6
ArduCopter/crash_check.pde

@ -110,7 +110,7 @@ void parachute_check() @@ -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() @@ -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() @@ -186,4 +186,4 @@ static void parachute_manual_release()
parachute_release();
}
#endif // PARACHUTE == ENABLED
#endif // PARACHUTE == ENABLED

Loading…
Cancel
Save