From ff40fa6aabe05d73a585adb5630468566ce5203d Mon Sep 17 00:00:00 2001 From: rmackay9 <rmackay9@yahoo.com> Date: Sat, 22 Dec 2012 17:57:11 +0900 Subject: [PATCH] ArduCopter: alt hold bug fix - should use 2x linear distance when calculating the desired rate Bug fix from Leonard. --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index e509580f85..ad0f1d7415 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -997,7 +997,7 @@ get_throttle_althold(int32_t target_alt, int16_t min_climb_rate, int16_t max_cli linear_distance = 250/(2*g.pi_alt_hold.kP()*g.pi_alt_hold.kP()); - if( altitude_error < linear_distance ) { + if( altitude_error < linear_distance*2 ) { desired_rate = g.pi_alt_hold.get_p(altitude_error); }else{ desired_rate = sqrt(2*250*(altitude_error-linear_distance));