mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: raise the default WP radius
with L1 a large radius doesn't mean it turns too early
This commit is contained in:
parent
292517b88b
commit
21ed86004a
@ -428,7 +428,7 @@
|
||||
// Navigation defaults
|
||||
//
|
||||
#ifndef WP_RADIUS_DEFAULT
|
||||
# define WP_RADIUS_DEFAULT 30
|
||||
# define WP_RADIUS_DEFAULT 90
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_RADIUS_DEFAULT
|
||||
|
Loading…
Reference in New Issue
Block a user