Browse Source

Plane: fixed zero throttle in QSTABILISE mode

master
Andrew Tridgell 9 years ago
parent
commit
4da798129e
  1. 4
      ArduPlane/quadplane.cpp

4
ArduPlane/quadplane.cpp

@ -416,8 +416,12 @@ void QuadPlane::hold_stabilize(float throttle_in) @@ -416,8 +416,12 @@ void QuadPlane::hold_stabilize(float throttle_in)
get_pilot_desired_yaw_rate_cds(),
smoothing_gain);
if (throttle_in <= 0) {
attitude_control->set_throttle_out_unstabilized(0, true, 0);
} else {
attitude_control->set_throttle_out(throttle_in, true, 0);
}
}
// quadplane stabilize mode
void QuadPlane::control_stabilize(void)

Loading…
Cancel
Save