mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: only ouput throttle to mask if armed
This commit is contained in:
parent
e189b17efb
commit
d08b395224
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue