From 69be1725b69c7892145f9e1a9b74885e9c03b263 Mon Sep 17 00:00:00 2001 From: dheideman Date: Mon, 18 Sep 2017 11:42:53 -0700 Subject: [PATCH] Sub: Disable input hold on disarm --- ArduSub/Sub.h | 1 + ArduSub/joystick.cpp | 8 ++++++++ ArduSub/motors.cpp | 3 +++ 3 files changed, 12 insertions(+) diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 3994062d47..e59845e21d 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -643,6 +643,7 @@ private: void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false); JSButton* get_button(uint8_t index); void default_js_buttons(void); + void clear_input_hold(); void init_barometer(bool save); void read_barometer(void); void init_rangefinder(void); diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index 90c10a6571..a0f13a1761 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -550,3 +550,11 @@ void Sub::set_neutral_controls() hal.rcin->set_overrides(channels, 10); } + +void Sub::clear_input_hold() +{ + xTrim = 0; + yTrim = 0; + zTrim = 0; + input_hold_engaged = false; +} diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index cb2704df2c..5180cf075c 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -120,6 +120,9 @@ void Sub::init_disarm_motors() // disable gps velocity based centrefugal force compensation ahrs.set_correct_centrifugal(false); hal.util->set_soft_armed(false); + + // clear input holds + clear_input_hold(); } // motors_output - send output to motors library which will adjust and send to ESCs and servos