mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Bug fix: When adjusting altitude, RTL then land will fail unless this var is reset to false.
This commit is contained in:
parent
1b9f75c844
commit
71f80f3a77
@ -400,6 +400,7 @@ static void set_mode(byte mode)
|
|||||||
|
|
||||||
// clearing value used to force the copter down in landing mode
|
// clearing value used to force the copter down in landing mode
|
||||||
landing_boost = 0;
|
landing_boost = 0;
|
||||||
|
reset_throttle_flag = false;
|
||||||
|
|
||||||
// do we want to come to a stop or pass a WP?
|
// do we want to come to a stop or pass a WP?
|
||||||
slow_wp = false;
|
slow_wp = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user