mirror of https://github.com/ArduPilot/ardupilot
Acro PI defaults
This commit is contained in:
parent
dd23883097
commit
0b4a3ccadb
|
@ -382,7 +382,30 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Rate Control
|
// Acro Rate Control
|
||||||
|
//
|
||||||
|
#ifndef ACRO_ROLL_P
|
||||||
|
# define ACRO_ROLL_P 0.145
|
||||||
|
#endif
|
||||||
|
#ifndef ACRO_ROLL_I
|
||||||
|
# define ACRO_ROLL_I 0.0
|
||||||
|
#endif
|
||||||
|
#ifndef ACRO_ROLL_IMAX
|
||||||
|
# define ACRO_ROLL_IMAX 15 // degrees
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ACRO_PITCH_P
|
||||||
|
# define ACRO_PITCH_P 0.145
|
||||||
|
#endif
|
||||||
|
#ifndef ACRO_PITCH_I
|
||||||
|
# define ACRO_PITCH_I 0 //0.18
|
||||||
|
#endif
|
||||||
|
#ifndef ACRO_PITCH_IMAX
|
||||||
|
# define ACRO_PITCH_IMAX 15 // degrees
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Stabilize Rate Control
|
||||||
//
|
//
|
||||||
#ifndef RATE_ROLL_P
|
#ifndef RATE_ROLL_P
|
||||||
# define RATE_ROLL_P 0.145
|
# define RATE_ROLL_P 0.145
|
||||||
|
|
Loading…
Reference in New Issue