From dbd47b2a309124a5946c01f3a0c1b4834623c241 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Mon, 15 Jul 2013 11:12:24 +1000
Subject: [PATCH] Plane: make TECS the default speed/height controller

---
 ArduPlane/ArduPlane.pde  | 6 ++++--
 ArduPlane/Attitude.pde   | 6 +++---
 ArduPlane/Parameters.pde | 4 ++--
 ArduPlane/defines.h      | 3 ++-
 4 files changed, 11 insertions(+), 8 deletions(-)

diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 4cae95ee4..3e0488245 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -802,7 +802,9 @@ static void fast_loop()
  */
 static void update_speed_height(void)
 {
-    if (g.alt_control_algorithm == ALT_CONTROL_TECS && auto_throttle_mode && !throttle_suppressed) 
+    if ((g.alt_control_algorithm == ALT_CONTROL_TECS ||
+         g.alt_control_algorithm == ALT_CONTROL_DEFAULT) &&
+        auto_throttle_mode && !throttle_suppressed) 
     {
 	    // Call TECS 50Hz update
         SpdHgt_Controller->update_50hz(relative_altitude());
@@ -1279,7 +1281,7 @@ static void update_alt()
     //	add_altitude_data(millis() / 100, g_gps->altitude / 10);
 
     // Update the speed & height controller states
-    if (g.alt_control_algorithm == ALT_CONTROL_TECS &&
+    if ((g.alt_control_algorithm == ALT_CONTROL_TECS || g.alt_control_algorithm == ALT_CONTROL_DEFAULT) &&
         auto_throttle_mode && !throttle_suppressed) {
         SpdHgt_Controller->update_pitch_throttle(target_altitude_cm - home.alt + (int32_t(g.alt_offset)*100), 
                                                  target_airspeed_cm,
diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde
index 7fb112226..2ce5161c8 100644
--- a/ArduPlane/Attitude.pde
+++ b/ArduPlane/Attitude.pde
@@ -360,7 +360,7 @@ static void calc_throttle()
         return;
     }
 
-    if (g.alt_control_algorithm == ALT_CONTROL_TECS) {
+    if (g.alt_control_algorithm == ALT_CONTROL_TECS || g.alt_control_algorithm == ALT_CONTROL_DEFAULT) {
         channel_throttle->servo_out = SpdHgt_Controller->get_throttle_demand();
     } else if (!alt_control_airspeed()) {
         int16_t throttle_target = aparm.throttle_cruise + throttle_nudge;
@@ -427,7 +427,7 @@ static void calc_nav_pitch()
 {
     // Calculate the Pitch of the plane
     // --------------------------------
-    if (g.alt_control_algorithm == ALT_CONTROL_TECS) {
+    if (g.alt_control_algorithm == ALT_CONTROL_TECS || g.alt_control_algorithm == ALT_CONTROL_DEFAULT) {
         nav_pitch_cd = SpdHgt_Controller->get_pitch_demand();
     } else if (alt_control_airspeed()) {
         nav_pitch_cd = -g.pidNavPitchAirspeed.get_pid(airspeed_error_cm);
@@ -887,5 +887,5 @@ static void demo_servos(uint8_t i)
 // return true if we should use airspeed for altitude/throttle control
 static bool alt_control_airspeed(void)
 {
-    return airspeed.use() && g.alt_control_algorithm == ALT_CONTROL_DEFAULT;
+    return airspeed.use() && g.alt_control_algorithm == ALT_CONTROL_AIRSPEED;
 }
diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde
index e897ad07a..3e572d0f3 100644
--- a/ArduPlane/Parameters.pde
+++ b/ArduPlane/Parameters.pde
@@ -163,8 +163,8 @@ const AP_Param::Info var_info[] PROGMEM = {
 
     // @Param: ALT_CTRL_ALG
     // @DisplayName: Altitude control algorithm
-    // @Description: This sets what algorithm will be used for altitude control. The default is to select the algorithm based on whether airspeed is enabled. If you set it to 1, then the airspeed based algorithm won't be used for altitude control, but airspeed can be used for other flight control functions. Setting it to 2 selects the new 'TECS' (total energy control system) altitude control, which works both with and without airspeed
-    // @Values: 0:Default Method,1:non-airspeed,2:TECS
+    // @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). If you set it to 1 then you will get the old (deprecated) non-airspeed based algorithm. If you set it to 3 then you will get the old (deprecated) airspeed based algorithm. Setting it to 2 selects the new 'TECS' (total energy control system) altitude control, which currently is equivalent to setting 0. Note that TECS is able to handle aircraft both with and without an airspeed sensor.
+    // @Values: 0:Automatic,1:non-airspeed(deprecated),2:TECS,3:airspeed(deprecated)
     // @User: Advanced
     GSCALAR(alt_control_algorithm, "ALT_CTRL_ALG",    ALT_CONTROL_DEFAULT),
 
diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h
index b8ff3fcc5..a7e18b6f3 100644
--- a/ArduPlane/defines.h
+++ b/ArduPlane/defines.h
@@ -255,7 +255,8 @@ enum log_messages {
 enum {
     ALT_CONTROL_DEFAULT      = 0,
     ALT_CONTROL_NON_AIRSPEED = 1,
-    ALT_CONTROL_TECS         = 2
+    ALT_CONTROL_TECS         = 2,
+    ALT_CONTROL_AIRSPEED     = 3
 };
 
 // attitude controller choice
-- 
GitLab