ArduCopter: modified altitude hold so that 1 second slow down period is executed after pilot moves throttle back into deadzone

This commit is contained in:
rmackay9 2012-08-18 21:45:49 +09:00
parent 4371fdda6c
commit 7a31e4e660

View File

@ -1824,12 +1824,16 @@ void update_throttle_mode(void)
break;
}
// allow 1 second of slow down after pilot moves throttle back into deadzone
if(reset_throttle_counter > 0){
reset_throttle_counter--;
// if 1 second has passed set the target altitude to the current altitude
if(reset_throttle_counter == 0){
force_new_altitude(max(current_loc.alt, 100));
}else{
nav_throttle = get_throttle_rate(0);
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost;
break;
}
}