mirror of https://github.com/ArduPilot/ardupilot
improved throttle PIDs
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1548 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
34f43934da
commit
9d5937db52
|
@ -378,13 +378,13 @@
|
||||||
# define THROTTLE_BARO_P .25
|
# define THROTTLE_BARO_P .25
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_BARO_I
|
#ifndef THROTTLE_BARO_I
|
||||||
# define THROTTLE_BARO_I 0.1
|
# define THROTTLE_BARO_I 0.04
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_BARO_D
|
#ifndef THROTTLE_BARO_D
|
||||||
# define THROTTLE_BARO_D 0.1
|
# define THROTTLE_BARO_D 0.1
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_BARO_IMAX
|
#ifndef THROTTLE_BARO_IMAX
|
||||||
# define THROTTLE_BARO_IMAX 150
|
# define THROTTLE_BARO_IMAX 100
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef THROTTLE_SONAR_P
|
#ifndef THROTTLE_SONAR_P
|
||||||
|
|
Loading…
Reference in New Issue