mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Added slow_wp default in AP mode
This commit is contained in:
parent
434b059586
commit
70d7a1f5d0
@ -245,6 +245,9 @@ static void reset_nav_params(void)
|
||||
|
||||
// Will be set by new command, used by loiter
|
||||
next_WP.alt = 0;
|
||||
|
||||
// We want to by default pass WPs
|
||||
slow_wp = false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user