ArduCopter: alt hold bug fix - should use 2x linear distance when calculating the desired rate

Bug fix from Leonard.
This commit is contained in:
rmackay9 2012-12-22 17:57:11 +09:00 committed by Andrew Tridgell
parent 68b62abd38
commit ff40fa6aab
1 changed files with 1 additions and 1 deletions

View File

@ -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()); 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); desired_rate = g.pi_alt_hold.get_p(altitude_error);
}else{ }else{
desired_rate = sqrt(2*250*(altitude_error-linear_distance)); desired_rate = sqrt(2*250*(altitude_error-linear_distance));