mirror of https://github.com/ArduPilot/ardupilot
updated Gains for Marco's loiter test
This commit is contained in:
parent
24345d4f43
commit
385828824d
|
@ -651,7 +651,7 @@
|
|||
// Loiter control gains
|
||||
//
|
||||
#ifndef LOITER_P
|
||||
# define LOITER_P .2 // was .25 in previous
|
||||
# define LOITER_P .8
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.0
|
||||
|
@ -664,10 +664,10 @@
|
|||
// Loiter Navigation control gains
|
||||
//
|
||||
#ifndef LOITER_RATE_P
|
||||
# define LOITER_RATE_P 3.0 //
|
||||
# define LOITER_RATE_P 3.5 //
|
||||
#endif
|
||||
#ifndef LOITER_RATE_I
|
||||
# define LOITER_RATE_I 0.1 // Wind control
|
||||
# define LOITER_RATE_I 0.2 // Wind control
|
||||
#endif
|
||||
#ifndef LOITER_RATE_D
|
||||
# define LOITER_RATE_D 0.00 //
|
||||
|
@ -680,10 +680,10 @@
|
|||
// WP Navigation control gains
|
||||
//
|
||||
#ifndef NAV_P
|
||||
# define NAV_P 3.0 //
|
||||
# define NAV_P 3.5 //
|
||||
#endif
|
||||
#ifndef NAV_I
|
||||
# define NAV_I 0.1 // Wind control
|
||||
# define NAV_I 0.2 // Wind control
|
||||
#endif
|
||||
#ifndef NAV_D
|
||||
# define NAV_D 0.00 //
|
||||
|
|
Loading…
Reference in New Issue