mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: allow control surfaces to move disarmed
allow tailsitter control surfaces to move in Q modes when shutdown
This commit is contained in:
parent
642a6acfcb
commit
328541769d
@ -42,16 +42,10 @@ void AP_MotorsTailsitter::output_to_motors()
|
||||
}
|
||||
switch (_spool_mode) {
|
||||
case SHUT_DOWN:
|
||||
_aileron = 0;
|
||||
_elevator = 0;
|
||||
_rudder = 0;
|
||||
_throttle = 0;
|
||||
break;
|
||||
case SPIN_WHEN_ARMED:
|
||||
// sends output to motors when armed but not flying
|
||||
_aileron = 0;
|
||||
_elevator = 0;
|
||||
_rudder = 0;
|
||||
_throttle = constrain_float(_spin_up_ratio, 0.0f, 1.0f) * _spin_min;
|
||||
break;
|
||||
case SPOOL_UP:
|
||||
|
Loading…
Reference in New Issue
Block a user