mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
updated Alt hold PIDs
This commit is contained in:
parent
0a538baeb2
commit
1df9f8488d
@ -509,10 +509,10 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef THR_HOLD_P
|
#ifndef THR_HOLD_P
|
||||||
# define THR_HOLD_P 0.5 //
|
# define THR_HOLD_P 0.4 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef THR_HOLD_I
|
#ifndef THR_HOLD_I
|
||||||
# define THR_HOLD_I 0.01 // with 4m error, 12.5s windup
|
# define THR_HOLD_I 0.02 // with 4m error, 12.5s windup
|
||||||
#endif
|
#endif
|
||||||
#ifndef THR_HOLD_IMAX
|
#ifndef THR_HOLD_IMAX
|
||||||
# define THR_HOLD_IMAX 300
|
# define THR_HOLD_IMAX 300
|
||||||
@ -520,10 +520,10 @@
|
|||||||
|
|
||||||
// RATE control
|
// RATE control
|
||||||
#ifndef THROTTLE_P
|
#ifndef THROTTLE_P
|
||||||
# define THROTTLE_P 0.8 //
|
# define THROTTLE_P 1.0 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_I
|
#ifndef THROTTLE_I
|
||||||
# define THROTTLE_I 0.10 // with 4m error, 12.5s windup
|
# define THROTTLE_I 0.0 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_IMAX
|
#ifndef THROTTLE_IMAX
|
||||||
# define THROTTLE_IMAX 50
|
# define THROTTLE_IMAX 50
|
||||||
|
Loading…
Reference in New Issue
Block a user