Browse Source

Plane: fixed use of HAL soft_armed

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
dc9e2a54f3
  1. 11
      ArduPlane/ArduPlane.pde

11
ArduPlane/ArduPlane.pde

@ -1561,7 +1561,7 @@ static void determine_is_flying(void) @@ -1561,7 +1561,7 @@ static void determine_is_flying(void)
gps.ground_speed() >= 5);
if(arming.is_armed()) {
if (hal.util->get_soft_armed()) {
// when armed, we need overwhelming evidence that we ARE NOT flying
isFlyingBool = airspeedMovement || gpsMovement;
@ -1576,16 +1576,13 @@ static void determine_is_flying(void) @@ -1576,16 +1576,13 @@ static void determine_is_flying(void)
static bool is_flying(void)
{
if(arming.is_armed()) {
if (hal.util->get_soft_armed()) {
// when armed, assume we're flying unless we probably aren't
return (isFlyingProbability >= 0.1f);
}
else
{
// when disarmed, assume we're not flying unless we probably are
return (isFlyingProbability >= 0.9f);
}
// when disarmed, assume we're not flying unless we probably are
return (isFlyingProbability >= 0.9f);
}

Loading…
Cancel
Save