mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Lowered Nav_P I term to ramp slower base on SIM
This commit is contained in:
parent
6c9e6f3f96
commit
54790bd981
@ -489,7 +489,7 @@
|
||||
# define NAV_P 3.0 //
|
||||
#endif
|
||||
#ifndef NAV_I
|
||||
# define NAV_I 0.25 // this feels really low, 4s to move 1 degree pitch...
|
||||
# define NAV_I 0.05 // Lowerd from .25 - saw lots of overshoot.
|
||||
#endif
|
||||
#ifndef NAV_IMAX
|
||||
# define NAV_IMAX 20 // degrees
|
||||
|
Loading…
Reference in New Issue
Block a user