mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: increase default CIRCLE_RATE to 20deg/sec
This commit is contained in:
parent
245bc3d3fd
commit
cd30103b76
@ -636,7 +636,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_RATE
|
||||
# define CIRCLE_RATE 5.0f // degrees per second turn rate
|
||||
# define CIRCLE_RATE 20.0f // degrees per second turn rate
|
||||
#endif
|
||||
|
||||
// Guided Mode
|
||||
|
Loading…
Reference in New Issue
Block a user