mirror of https://github.com/ArduPilot/ardupilot
Lowered Nav_P I term to ramp slower base on SIM
This commit is contained in:
parent
27d9bc92f3
commit
a8d622d8e6
|
@ -489,7 +489,7 @@
|
||||||
# define NAV_P 3.0 //
|
# define NAV_P 3.0 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_I
|
#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
|
#endif
|
||||||
#ifndef NAV_IMAX
|
#ifndef NAV_IMAX
|
||||||
# define NAV_IMAX 20 // degrees
|
# define NAV_IMAX 20 // degrees
|
||||||
|
|
Loading…
Reference in New Issue