From f65390920ac776a31104223e18e73665251df523 Mon Sep 17 00:00:00 2001
From: Jason Short <jasonshort@gmail.com>
Date: Thu, 22 Sep 2011 23:10:55 -0700
Subject: [PATCH] Added a default, but low throttle cruise value Added a clear
 integrator for Rate I to prevent tip ups at launch.

---
 ArduCopter/ArduCopter.pde  | 3 ++-
 ArduCopter/Attitude.pde    | 1 -
 ArduCopter/Parameters.h    | 2 +-
 ArduCopter/config.h        | 6 ++++++
 ArduCopter/motors_quad.pde | 1 -
 5 files changed, 9 insertions(+), 4 deletions(-)

diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index f5a955e3b1..d3b2dfc1ef 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -1080,7 +1080,6 @@ void update_roll_pitch_mode(void)
 			g.rc_2.servo_out 	= get_stabilize_pitch(control_pitch);
 			break;
 	}
-
 }
 
 
@@ -1093,6 +1092,8 @@ void update_throttle_mode(void)
 			if (g.rc_3.control_in > 0){
 				g.rc_3.servo_out = g.rc_3.control_in + get_angle_boost();
 			}else{
+				g.pi_rate_roll.reset_I();
+				g.pi_rate_pitch.reset_I();
 				g.rc_3.servo_out = 0;
 			}
 			// reset the timer to throttle so that we never get fast I term run-ups
diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 8200e98452..0a1268246d 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -25,7 +25,6 @@ get_stabilize_roll(long target_angle)
 
 	// output control:
 	return (int)constrain(rate, -2500, 2500);
-
 }
 
 static int
diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h
index d9a5bca530..50de454176 100644
--- a/ArduCopter/Parameters.h
+++ b/ArduCopter/Parameters.h
@@ -317,7 +317,7 @@ public:
 	throttle_fs_enabled		(THROTTLE_FAILSAFE,			k_param_throttle_fs_enabled,			PSTR("THR_FAILSAFE")),
 	throttle_fs_action		(THROTTLE_FAILSAFE_ACTION,	k_param_throttle_fs_action, 			PSTR("THR_FS_ACTION")),
 	throttle_fs_value 		(THROTTLE_FS_VALUE,			k_param_throttle_fs_value, 				PSTR("THR_FS_VALUE")),
-	throttle_cruise			(100,						k_param_throttle_cruise,				PSTR("TRIM_THROTTLE")),
+	throttle_cruise			(THROTTLE_CRUISE,			k_param_throttle_cruise,				PSTR("TRIM_THROTTLE")),
 
     flight_mode1            (FLIGHT_MODE_1,             k_param_flight_mode1,					PSTR("FLTMODE1")),
     flight_mode2            (FLIGHT_MODE_2,             k_param_flight_mode2,					PSTR("FLTMODE2")),
diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index 041efcdb8d..fa608e81e4 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -509,6 +509,12 @@
 //////////////////////////////////////////////////////////////////////////////
 // Throttle control gains
 //
+
+
+#ifndef THROTTLE_CRUISE
+# define THROTTLE_CRUISE	350			//
+#endif
+
 #ifndef THROTTLE_P
 # define THROTTLE_P		0.6			//
 #endif
diff --git a/ArduCopter/motors_quad.pde b/ArduCopter/motors_quad.pde
index 5344a08f63..d5af159ad4 100644
--- a/ArduCopter/motors_quad.pde
+++ b/ArduCopter/motors_quad.pde
@@ -4,7 +4,6 @@
 
 static void output_motors_armed()
 {
-
 	int roll_out, pitch_out;
 	int out_min = g.rc_3.radio_min;
 	int out_max = g.rc_3.radio_max;