From 47d5de353dca840bd59ecf02abbc8719e9d704eb Mon Sep 17 00:00:00 2001 From: dheideman Date: Mon, 30 Oct 2017 13:07:58 -0700 Subject: [PATCH] Sub: Set neutral controls when switching to manual/acro mode --- ArduSub/control_acro.cpp | 4 ++++ ArduSub/control_manual.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/ArduSub/control_acro.cpp b/ArduSub/control_acro.cpp index ca7826428e..63b01d78ca 100644 --- a/ArduSub/control_acro.cpp +++ b/ArduSub/control_acro.cpp @@ -11,6 +11,10 @@ bool Sub::acro_init() // set target altitude to zero for reporting pos_control.set_alt_target(0); + // attitude hold inputs become thrust inputs in acro mode + // set to neutral to prevent chaotic behavior (esp. roll/pitch) + set_neutral_controls(); + return true; } diff --git a/ArduSub/control_manual.cpp b/ArduSub/control_manual.cpp index 75a39a506f..d7bc79d279 100644 --- a/ArduSub/control_manual.cpp +++ b/ArduSub/control_manual.cpp @@ -6,6 +6,10 @@ bool Sub::manual_init() // set target altitude to zero for reporting pos_control.set_alt_target(0); + // attitude hold inputs become thrust inputs in manual mode + // set to neutral to prevent chaotic behavior (esp. roll/pitch) + set_neutral_controls(); + return true; }