From 5602fcba664d6591674d2fd82dbd9986e5eab644 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Sep 2023 07:30:27 +1000 Subject: [PATCH] Plane: use deadzone in stick mixing this prevents small RC input deviations from impacting non-pilot controlled modes via stick mixing --- ArduPlane/Attitude.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 0b51098b43..6d078e9847 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -259,7 +259,7 @@ void Plane::stabilize_stick_mixing_fbw() // non-linear and ends up as 2x the maximum, to ensure that // the user can direct the plane in any direction with stick // mixing. - float roll_input = channel_roll->norm_input(); + float roll_input = channel_roll->norm_input_dz(); if (roll_input > 0.5f) { roll_input = (3*roll_input - 1); } else if (roll_input < -0.5f) { @@ -273,7 +273,7 @@ void Plane::stabilize_stick_mixing_fbw() return; } - float pitch_input = channel_pitch->norm_input(); + float pitch_input = channel_pitch->norm_input_dz(); if (pitch_input > 0.5f) { pitch_input = (3*pitch_input - 1); } else if (pitch_input < -0.5f) {