From 0c520f89d6b0773f1577b81d0550af9deea45a1b Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Sat, 30 Mar 2013 09:07:18 +0900
Subject: [PATCH] Copter: bug fix for alt_hold being passed as int16_t to
 get_throttle_althold_with_slew

---
 ArduCopter/Attitude.pde | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 02fd3ab0b..4258bc5a0 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -1053,7 +1053,7 @@ get_throttle_althold(int32_t target_alt, int16_t min_climb_rate, int16_t max_cli
 // get_throttle_althold_with_slew - altitude controller with slew to avoid step changes in altitude target
 // calls normal althold controller which updates accel based throttle controller targets
 static void
-get_throttle_althold_with_slew(int16_t target_alt, int16_t min_climb_rate, int16_t max_climb_rate)
+get_throttle_althold_with_slew(int32_t target_alt, int16_t min_climb_rate, int16_t max_climb_rate)
 {
     // limit target altitude change
     controller_desired_alt += constrain(target_alt-controller_desired_alt, min_climb_rate*0.02, max_climb_rate*0.02);
-- 
GitLab