ArduCopter: allow alt hold to be engaged with alt < 1m because sometimes we get baro drift.
Also initialisation of target altitude is done in set_throttle_mode function.
This commit is contained in:
parent
b4e5176e2a
commit
b36eb406d4
@ -456,7 +456,6 @@ static void set_mode(byte mode)
|
||||
set_yaw_mode(ALT_HOLD_YAW);
|
||||
set_roll_pitch_mode(ALT_HOLD_RP);
|
||||
set_throttle_mode(ALT_HOLD_THR);
|
||||
force_new_altitude(max(current_loc.alt, 100));
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
|
Loading…
Reference in New Issue
Block a user