AP_MotorsMulticopter: check interlock state in output_motor_mask

This commit is contained in:
Iampete1 2022-01-27 15:50:09 +00:00 committed by Randy Mackay
parent 1ca1707f9f
commit 8af5f5b2d7
1 changed files with 1 additions and 1 deletions

View File

@ -758,7 +758,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)) && armed()) {
if ((mask & (1U << i)) && armed() && get_interlock()) {
/*
apply rudder mixing differential thrust
copter frame roll is plane frame yaw as this only