mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Gain adjustments for 3d frame.
This commit is contained in:
parent
3932e8b2a1
commit
f369a02aab
@ -542,10 +542,10 @@
|
|||||||
|
|
||||||
|
|
||||||
#ifndef STABILIZE_D
|
#ifndef STABILIZE_D
|
||||||
# define STABILIZE_D .12
|
# define STABILIZE_D .06
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Jasons default values that are good for smaller payload motors.
|
// Good for smaller payload motors.
|
||||||
#ifndef STABILIZE_ROLL_P
|
#ifndef STABILIZE_ROLL_P
|
||||||
# define STABILIZE_ROLL_P 4.5
|
# define STABILIZE_ROLL_P 4.5
|
||||||
#endif
|
#endif
|
||||||
@ -587,10 +587,10 @@
|
|||||||
# define RATE_ROLL_I 0.18
|
# define RATE_ROLL_I 0.18
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_D
|
#ifndef RATE_ROLL_D
|
||||||
# define RATE_ROLL_D 0.0
|
# define RATE_ROLL_D 0.0025
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_IMAX
|
#ifndef RATE_ROLL_IMAX
|
||||||
# define RATE_ROLL_IMAX 15 // degrees
|
# define RATE_ROLL_IMAX 5 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_PITCH_P
|
#ifndef RATE_PITCH_P
|
||||||
@ -600,10 +600,10 @@
|
|||||||
# define RATE_PITCH_I 0.18
|
# define RATE_PITCH_I 0.18
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_D
|
#ifndef RATE_PITCH_D
|
||||||
# define RATE_PITCH_D 0.0 // 0.002
|
# define RATE_PITCH_D 0.0025
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_IMAX
|
#ifndef RATE_PITCH_IMAX
|
||||||
# define RATE_PITCH_IMAX 15 // degrees
|
# define RATE_PITCH_IMAX 5 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_YAW_P
|
#ifndef RATE_YAW_P
|
||||||
|
Loading…
Reference in New Issue
Block a user