AP_Motors: only ouput throttle to mask if armed

This commit is contained in:
Peter Hall 2020-01-19 16:45:36 +00:00 committed by Andrew Tridgell
parent e189b17efb
commit d08b395224
1 changed files with 1 additions and 1 deletions

View File

@ -737,7 +737,7 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float r
for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
if (motor_enabled[i]) {
if (mask & (1U << i)) {
if ((mask & (1U << i)) && armed()) {
/*
apply rudder mixing differential thrust
copter frame roll is plane frame yaw as this only