Plane: fixed zero throttle in QSTABILISE mode

This commit is contained in:
Andrew Tridgell 2016-01-06 10:32:25 +11:00
parent cfb74406b6
commit 4da798129e
1 changed files with 5 additions and 1 deletions

View File

@ -416,7 +416,11 @@ void QuadPlane::hold_stabilize(float throttle_in)
get_pilot_desired_yaw_rate_cds(),
smoothing_gain);
attitude_control->set_throttle_out(throttle_in, true, 0);
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