mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
removed unused defines
lowered default Loiter gain
This commit is contained in:
parent
569ff5046f
commit
154411c96c
@ -487,13 +487,6 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// experimental feature for
|
|
||||||
#ifndef WIND_COMP_STAB
|
|
||||||
# define WIND_COMP_STAB 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Attitude Control
|
// Attitude Control
|
||||||
//
|
//
|
||||||
@ -618,10 +611,10 @@
|
|||||||
// Loiter control gains
|
// Loiter control gains
|
||||||
//
|
//
|
||||||
#ifndef LOITER_P
|
#ifndef LOITER_P
|
||||||
# define LOITER_P 2.4 // was .25 in previous
|
# define LOITER_P 2.0 // was .25 in previous
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_I
|
#ifndef LOITER_I
|
||||||
# define LOITER_I 0.1 // Wind control
|
# define LOITER_I 0.05 // Wind control
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_IMAX
|
#ifndef LOITER_IMAX
|
||||||
# define LOITER_IMAX 30 // degrees°
|
# define LOITER_IMAX 30 // degrees°
|
||||||
|
Loading…
Reference in New Issue
Block a user