mirror of https://github.com/ArduPilot/ardupilot
ACM: changed alt hold initialization of altitude to be immediate
This commit is contained in:
parent
68d210660e
commit
3c1f4b1ad7
|
@ -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(¤t_loc);
|
force_new_altitude(max(current_loc.alt, 100));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
|
|
Loading…
Reference in New Issue