ArduCopter: alt hold bug fix - removed reset next_WP in init_home
This commit is contained in:
parent
41017442f8
commit
889d1bb36c
@ -208,9 +208,6 @@ static void init_home()
|
||||
// Save prev loc this makes the calcs look better before commands are loaded
|
||||
prev_WP = home;
|
||||
|
||||
// in case we RTL
|
||||
next_WP = home;
|
||||
|
||||
// Load home for a default guided_WP
|
||||
// -------------
|
||||
guided_WP = home;
|
||||
|
Loading…
Reference in New Issue
Block a user