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 450f89ec5d
commit 5ad7320505

View File

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