ACM: changed alt hold initialization of altitude to be immediate

This commit is contained in:
Jason Short 2012-03-10 12:44:18 -08:00
parent 68d210660e
commit 3c1f4b1ad7
1 changed files with 1 additions and 1 deletions

View File

@ -447,7 +447,7 @@ static void set_mode(byte mode)
roll_pitch_mode = ALT_HOLD_RP; roll_pitch_mode = ALT_HOLD_RP;
throttle_mode = ALT_HOLD_THR; throttle_mode = ALT_HOLD_THR;
set_next_WP(&current_loc); force_new_altitude(max(current_loc.alt, 100));
break; break;
case AUTO: case AUTO: