mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: always stabilize with tailsitters
This commit is contained in:
parent
7992a21f6f
commit
b15b11e32d
@ -693,7 +693,12 @@ void QuadPlane::hold_stabilize(float throttle_in)
|
|||||||
|
|
||||||
if (throttle_in <= 0) {
|
if (throttle_in <= 0) {
|
||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||||
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
if (is_tailsitter()) {
|
||||||
|
// always stabilize with tailsitters so we can do belly takeoffs
|
||||||
|
attitude_control->set_throttle_out(0, true, 0);
|
||||||
|
} else {
|
||||||
|
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
attitude_control->set_throttle_out(throttle_in, true, 0);
|
attitude_control->set_throttle_out(throttle_in, true, 0);
|
||||||
|
Loading…
Reference in New Issue
Block a user