Plane: Remove ALT_MIX

Closes #4998, and fix a tab/spaces error on the previous parameter
This commit is contained in:
Michael du Breuil 2017-02-09 23:23:54 -07:00 committed by Andrew Tridgell
parent 9535b45cc9
commit 7a1cbf76d3
2 changed files with 7 additions and 17 deletions

View File

@ -242,15 +242,6 @@ const AP_Param::Info Plane::var_info[] = {
// @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: ALT_CTRL_ALG
// @DisplayName: Altitude control algorithm
// @Description: This sets what algorithm will be used for altitude control. The default is zero, which selects the most appropriate algorithm for your airframe. Currently the default is to use TECS (total energy control system). From time to time we will add other experimental altitude control algorithms which will be selected using this parameter.

View File

@ -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