From d11b07bd4f7e970d78a52ef98eb5875317b20c3d Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Sun, 4 Dec 2016 11:05:37 -0500 Subject: [PATCH] Sub: Remove PILOT_THR_BEHAVIOR parameter and disable auto_disarm_check() --- ArduSub/Parameters.cpp | 8 -------- ArduSub/Parameters.h | 4 ---- 2 files changed, 12 deletions(-) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index eaa601ae44..96898d00a9 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -84,14 +84,6 @@ const AP_Param::Info Sub::var_info[] = { // @Increment: .5 GSCALAR(throttle_filt, "PILOT_THR_FILT", 0), - // @Param: PILOT_THR_BHV - // @DisplayName: Throttle stick behavior - // @Description: Bitmask containing various throttle stick options. Add up the values for options that you want. - // @User: Standard - // @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection - // @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection - GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0), - // @Group: SERIAL // @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp GOBJECT(serial_manager, "SERIAL", AP_SerialManager), diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 15c1a09aef..4acd6cb731 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -240,9 +240,6 @@ public: k_param_autotune_axis_bitmask, // Disabled k_param_autotune_aggressiveness, // Disabled k_param_autotune_min_d, // Disabled - - - k_param_throttle_behavior, // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Remove }; AP_Int16 format_version; @@ -257,7 +254,6 @@ public: #endif AP_Float throttle_filt; - AP_Int16 throttle_behavior; AP_Float rangefinder_gain;