mirror of
https://github.com/okalachev/flix.git
synced 2026-02-17 15:41:32 +00:00
Move yaw dead zone handling from mavlink to control subsystem
So yaw dead zone works the same for rc and mavlink.
This commit is contained in:
@@ -75,6 +75,8 @@ void interpretControls() {
|
||||
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture
|
||||
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture
|
||||
|
||||
if (abs(controlYaw) < 0.1) controlYaw = 0; // yaw dead zone
|
||||
|
||||
thrustTarget = controlThrottle;
|
||||
|
||||
if (mode == STAB) {
|
||||
|
||||
Reference in New Issue
Block a user