From 7a1cbf76d34eb9d3e0e99d4f515c3218ac7d5ea6 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 9 Feb 2017 23:23:54 -0700 Subject: [PATCH] Plane: Remove ALT_MIX Closes #4998, and fix a tab/spaces error on the previous parameter --- ArduPlane/Parameters.cpp | 21 ++++++--------------- ArduPlane/Parameters.h | 3 +-- 2 files changed, 7 insertions(+), 17 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index efc27fd495..35c66dfcb0 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -235,21 +235,12 @@ const AP_Param::Info Plane::var_info[] = { // @User: Advanced GSCALAR(use_reverse_thrust, "USE_REV_THRUST", USE_REVERSE_THRUST_AUTO_LAND_APPROACH), - // @Param: NAV_CONTROLLER - // @DisplayName: Navigation controller selection - // @Description: Which navigation controller to enable. Currently the only navigation controller available is L1. From time to time other experimental controllers will be added which are selected using this parameter. - // @Values: 0:Default,1:L1Controller - // @User: Standard - GSCALAR(nav_controller, "NAV_CONTROLLER", AP_Navigation::CONTROLLER_L1), - - // @Param: ALT_MIX - // @DisplayName: GPS to Baro Mix - // @Description: The percent of mixing between GPS altitude and baro altitude. 0 = 100% gps, 1 = 100% baro. It is highly recommend that you not change this from the default of 1, as GPS altitude is notoriously unreliable. The only time I would recommend changing this is if you have a high altitude enabled GPS, and you are dropping a plane from a high altitude balloon many kilometers off the ground. - // @Units: Percent - // @Range: 0 1 - // @Increment: 0.1 - // @User: Advanced - GSCALAR(altitude_mix, "ALT_MIX", ALTITUDE_MIX), + // @Param: NAV_CONTROLLER + // @DisplayName: Navigation controller selection + // @Description: Which navigation controller to enable. Currently the only navigation controller available is L1. From time to time other experimental controllers will be added which are selected using this parameter. + // @Values: 0:Default,1:L1Controller + // @User: Standard + GSCALAR(nav_controller, "NAV_CONTROLLER", AP_Navigation::CONTROLLER_L1), // @Param: ALT_CTRL_ALG // @DisplayName: Altitude control algorithm diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 73646f3a38..4443384fba 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -189,7 +189,7 @@ public: // 130: Sensor parameters // k_param_imu = 130, // unused - k_param_altitude_mix, + k_param_altitude_mix, // deprecated k_param_compass_enabled, k_param_compass, @@ -393,7 +393,6 @@ public: // Estimation // - AP_Float altitude_mix; AP_Int8 alt_control_algorithm; // Waypoints