Browse Source

Copter: increase chance that parachute will deploy

Previously a single moment where the vehicle was within 30deg of the target could cause the parachute release counter to reset to zero.  This change makes the parachute release if it is spending at least half it's time with more than a 30degree angle error.
mission-4.1.18
Leonard Hall 9 years ago committed by Randy Mackay
parent
commit
1f2d17e8e7
  1. 4
      ArduCopter/crash_check.cpp

4
ArduCopter/crash_check.cpp

@ -101,7 +101,9 @@ void Copter::parachute_check() @@ -101,7 +101,9 @@ void Copter::parachute_check()
// check for angle error over 30 degrees
const float angle_error = attitude_control.get_att_error_angle_deg();
if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
control_loss_count = 0;
if (control_loss_count > 0) {
control_loss_count--;
}
return;
}

Loading…
Cancel
Save