From 5784abde1f1ff2948d49fe5715bb68845e9c0752 Mon Sep 17 00:00:00 2001 From: MattKear Date: Mon, 3 Jun 2024 20:13:43 +0100 Subject: [PATCH] AP_Motors: Heli dual: Constrain cyclic roll for intermeshing --- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 3bc2ab84e7..f2cc35f224 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -404,7 +404,8 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c pitch_out = _cyclic_max/4500.0f; limit.pitch = true; } - } else { + } + if (_dual_mode != AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE) { if (roll_out < -_cyclic_max/4500.0f) { roll_out = -_cyclic_max/4500.0f; limit.roll = true;