From cfaf08ad31dc2295cf525b6905529b0659eb6336 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Fri, 25 Nov 2016 19:04:49 -0500 Subject: [PATCH] Sub: Remove frame_orientation parameter --- ArduSub/Parameters.cpp | 7 ------- ArduSub/Parameters.h | 2 -- 2 files changed, 9 deletions(-) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index a6beb4a27b..034277bcb3 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -418,13 +418,6 @@ const AP_Param::Info Sub::var_info[] = { // @Range: 0 32767 GSCALAR(radio_tuning_high, "TUNE_HIGH", 1000), - // @Param: FRAME - // @DisplayName: Frame Orientation (+, X or V) - // @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters. - // @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B (New) - // @User: Standard - GSCALAR(frame_orientation, "FRAME", AP_MOTORS_X_FRAME), - // @Param: CH7_OPT // @DisplayName: Channel 7 option // @Description: Select which function if performed when CH7 is above 1800 pwm diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index ccb80d0769..b1711e2a38 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -160,7 +160,6 @@ public: // k_param_compass_enabled, k_param_compass, - k_param_frame_orientation, k_param_fs_batt_voltage, k_param_ch7_option, k_param_super_simple = 155, @@ -366,7 +365,6 @@ public: AP_Int8 radio_tuning; AP_Int16 radio_tuning_high; AP_Int16 radio_tuning_low; - AP_Int8 frame_orientation; AP_Int8 ch7_option; AP_Int8 ch8_option; AP_Int8 ch9_option;