Browse Source

Plane: fixed throttle suppression for AUTO_FBW_STEER=1

master
Andrew Tridgell 12 years ago
parent
commit
e455ee0a94
  1. 7
      ArduPlane/Attitude.pde

7
ArduPlane/Attitude.pde

@ -540,7 +540,12 @@ static bool suppress_throttle(void) @@ -540,7 +540,12 @@ static bool suppress_throttle(void)
return false;
}
if (control_mode==AUTO && !g.auto_fbw_steer && takeoff_complete == false && auto_takeoff_check()) {
if (control_mode==AUTO && g.auto_fbw_steer) {
// user has throttle control
return false;
}
if (control_mode==AUTO && takeoff_complete == false && auto_takeoff_check()) {
// we're in auto takeoff
throttle_suppressed = false;
if (hold_course_cd != -1) {

Loading…
Cancel
Save