mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: integrate parachute alt_min units change
This commit is contained in:
parent
879d447404
commit
01e5ae6e5c
@ -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
|
||||
#endif // PARACHUTE == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user