mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ACM: config.h = updated default gains
More yaw rate control
This commit is contained in:
parent
b5156185cc
commit
3e57f8afd8
@ -76,6 +76,10 @@
|
|||||||
#ifndef FRAME_ORIENTATION
|
#ifndef FRAME_ORIENTATION
|
||||||
# define FRAME_ORIENTATION X_FRAME
|
# define FRAME_ORIENTATION X_FRAME
|
||||||
#endif
|
#endif
|
||||||
|
#ifndef TOY_EDF
|
||||||
|
# define TOY_EDF DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// IMU Selection
|
// IMU Selection
|
||||||
@ -690,33 +694,33 @@
|
|||||||
// Stabilize Rate Control
|
// Stabilize Rate Control
|
||||||
//
|
//
|
||||||
#ifndef RATE_ROLL_P
|
#ifndef RATE_ROLL_P
|
||||||
# define RATE_ROLL_P 0.18
|
# define RATE_ROLL_P 0.185
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_I
|
#ifndef RATE_ROLL_I
|
||||||
# define RATE_ROLL_I 0.0
|
# define RATE_ROLL_I 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_D
|
#ifndef RATE_ROLL_D
|
||||||
# define RATE_ROLL_D 0.005
|
# define RATE_ROLL_D 0.008
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_IMAX
|
#ifndef RATE_ROLL_IMAX
|
||||||
# define RATE_ROLL_IMAX 5.0 // degrees
|
# define RATE_ROLL_IMAX 5.0 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_PITCH_P
|
#ifndef RATE_PITCH_P
|
||||||
# define RATE_PITCH_P 0.18
|
# define RATE_PITCH_P 0.185
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_I
|
#ifndef RATE_PITCH_I
|
||||||
# define RATE_PITCH_I 0.0
|
# define RATE_PITCH_I 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_D
|
#ifndef RATE_PITCH_D
|
||||||
# define RATE_PITCH_D 0.005
|
# define RATE_PITCH_D 0.008
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_IMAX
|
#ifndef RATE_PITCH_IMAX
|
||||||
# define RATE_PITCH_IMAX 5.0 // degrees
|
# define RATE_PITCH_IMAX 5.0 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_YAW_P
|
#ifndef RATE_YAW_P
|
||||||
# define RATE_YAW_P .13
|
# define RATE_YAW_P .25
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_YAW_I
|
#ifndef RATE_YAW_I
|
||||||
# define RATE_YAW_I 0.02
|
# define RATE_YAW_I 0.02
|
||||||
@ -811,7 +815,7 @@
|
|||||||
# define ALT_HOLD_P 0.3 // .5
|
# define ALT_HOLD_P 0.3 // .5
|
||||||
#endif
|
#endif
|
||||||
#ifndef ALT_HOLD_I
|
#ifndef ALT_HOLD_I
|
||||||
# define ALT_HOLD_I 0.038
|
# define ALT_HOLD_I 0.04
|
||||||
#endif
|
#endif
|
||||||
#ifndef ALT_HOLD_IMAX
|
#ifndef ALT_HOLD_IMAX
|
||||||
# define ALT_HOLD_IMAX 300
|
# define ALT_HOLD_IMAX 300
|
||||||
@ -825,7 +829,7 @@
|
|||||||
# define THROTTLE_I 0.03
|
# define THROTTLE_I 0.03
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_D
|
#ifndef THROTTLE_D
|
||||||
# define THROTTLE_D 0.0 //
|
# define THROTTLE_D 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_IMAX
|
#ifndef THROTTLE_IMAX
|
||||||
# define THROTTLE_IMAX 300
|
# define THROTTLE_IMAX 300
|
||||||
|
Loading…
Reference in New Issue
Block a user