Browse Source

updated Gains for Marco's loiter test

master
Jason Short 13 years ago
parent
commit
385828824d
  1. 14
      ArduCopter/config.h

14
ArduCopter/config.h

@ -651,7 +651,7 @@
// Loiter control gains // Loiter control gains
// //
#ifndef LOITER_P #ifndef LOITER_P
# define LOITER_P .2 // was .25 in previous # define LOITER_P .8
#endif #endif
#ifndef LOITER_I #ifndef LOITER_I
# define LOITER_I 0.0 # define LOITER_I 0.0
@ -664,26 +664,26 @@
// Loiter Navigation control gains // Loiter Navigation control gains
// //
#ifndef LOITER_RATE_P #ifndef LOITER_RATE_P
# define LOITER_RATE_P 3.0 // # define LOITER_RATE_P 3.5 //
#endif #endif
#ifndef LOITER_RATE_I #ifndef LOITER_RATE_I
# define LOITER_RATE_I 0.1 // Wind control # define LOITER_RATE_I 0.2 // Wind control
#endif #endif
#ifndef LOITER_RATE_D #ifndef LOITER_RATE_D
# define LOITER_RATE_D 0.00 // # define LOITER_RATE_D 0.00 //
#endif #endif
#ifndef LOITER_RATE_IMAX #ifndef LOITER_RATE_IMAX
# define LOITER_RATE_IMAX 30 // degrees # define LOITER_RATE_IMAX 30 // degrees
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// WP Navigation control gains // WP Navigation control gains
// //
#ifndef NAV_P #ifndef NAV_P
# define NAV_P 3.0 // # define NAV_P 3.5 //
#endif #endif
#ifndef NAV_I #ifndef NAV_I
# define NAV_I 0.1 // Wind control # define NAV_I 0.2 // Wind control
#endif #endif
#ifndef NAV_D #ifndef NAV_D
# define NAV_D 0.00 // # define NAV_D 0.00 //

Loading…
Cancel
Save