mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Plane: fixed zero throttle in QSTABILISE mode
This commit is contained in:
parent
cfb74406b6
commit
4da798129e
@ -416,8 +416,12 @@ void QuadPlane::hold_stabilize(float throttle_in)
|
|||||||
get_pilot_desired_yaw_rate_cds(),
|
get_pilot_desired_yaw_rate_cds(),
|
||||||
smoothing_gain);
|
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);
|
attitude_control->set_throttle_out(throttle_in, true, 0);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// quadplane stabilize mode
|
// quadplane stabilize mode
|
||||||
void QuadPlane::control_stabilize(void)
|
void QuadPlane::control_stabilize(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user