mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
Better Tuning for default Quad
This commit is contained in:
parent
3444b7fdca
commit
45f9ab05f8
@ -403,43 +403,43 @@
|
|||||||
// Attitude Control
|
// Attitude Control
|
||||||
//
|
//
|
||||||
#ifndef STABILIZE_ROLL_P
|
#ifndef STABILIZE_ROLL_P
|
||||||
# define STABILIZE_ROLL_P 4.0
|
# define STABILIZE_ROLL_P 4.2
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_ROLL_I
|
#ifndef STABILIZE_ROLL_I
|
||||||
# define STABILIZE_ROLL_I 0.02
|
# define STABILIZE_ROLL_I 0.008
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_ROLL_IMAX
|
#ifndef STABILIZE_ROLL_IMAX
|
||||||
# define STABILIZE_ROLL_IMAX 1.5 // degrees
|
# define STABILIZE_ROLL_IMAX 3 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef STABILIZE_PITCH_P
|
#ifndef STABILIZE_PITCH_P
|
||||||
# define STABILIZE_PITCH_P 4.0
|
# define STABILIZE_PITCH_P 4.2
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_PITCH_I
|
#ifndef STABILIZE_PITCH_I
|
||||||
# define STABILIZE_PITCH_I 0.02
|
# define STABILIZE_PITCH_I 0.008
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_PITCH_IMAX
|
#ifndef STABILIZE_PITCH_IMAX
|
||||||
# define STABILIZE_PITCH_IMAX 1.5 // degrees
|
# define STABILIZE_PITCH_IMAX 3 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Rate Control
|
// Rate Control
|
||||||
//
|
//
|
||||||
#ifndef RATE_ROLL_P
|
#ifndef RATE_ROLL_P
|
||||||
# define RATE_ROLL_P 0.13
|
# define RATE_ROLL_P 0.14
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_I
|
#ifndef RATE_ROLL_I
|
||||||
# define RATE_ROLL_I 0.0
|
# define RATE_ROLL_I 0.18
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_IMAX
|
#ifndef RATE_ROLL_IMAX
|
||||||
# define RATE_ROLL_IMAX 15 // degrees
|
# define RATE_ROLL_IMAX 15 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_PITCH_P
|
#ifndef RATE_PITCH_P
|
||||||
# define RATE_PITCH_P 0.13
|
# define RATE_PITCH_P 0.14
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_I
|
#ifndef RATE_PITCH_I
|
||||||
# define RATE_PITCH_I 0.0
|
# define RATE_PITCH_I 0.18
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_IMAX
|
#ifndef RATE_PITCH_IMAX
|
||||||
# define RATE_PITCH_IMAX 15 // degrees
|
# define RATE_PITCH_IMAX 15 // degrees
|
||||||
|
Loading…
Reference in New Issue
Block a user