Browse Source

Plane: fixed LOITER_TURNS counter for counter-clockwise loiter

thanks to Iskess for finding this bug!
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
f51478ee1d
  1. 2
      ArduPlane/navigation.pde

2
ArduPlane/navigation.pde

@ -37,7 +37,7 @@ static void loiter_angle_update(void) @@ -37,7 +37,7 @@ static void loiter_angle_update(void)
loiter.old_target_bearing_cd = target_bearing_cd;
loiter_delta_cd = wrap_180_cd(loiter_delta_cd);
loiter.sum_cd += loiter_delta_cd;
loiter.sum_cd += loiter_delta_cd * loiter.direction;
}
//****************************************************************

Loading…
Cancel
Save