mirror of https://github.com/ArduPilot/ardupilot
lowered Pitch max for nav
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1894 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
7aa34211b6
commit
e9702efada
|
@ -285,7 +285,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef ACRO_RATE_YAW_P
|
#ifndef ACRO_RATE_YAW_P
|
||||||
# define ACRO_RATE_YAW_P .1 // used to control response in turning
|
# define ACRO_RATE_YAW_P .13 // used to control response in turning
|
||||||
#endif
|
#endif
|
||||||
#ifndef ACRO_RATE_YAW_I
|
#ifndef ACRO_RATE_YAW_I
|
||||||
# define ACRO_RATE_YAW_I 0.0
|
# define ACRO_RATE_YAW_I 0.0
|
||||||
|
@ -353,7 +353,7 @@
|
||||||
//
|
//
|
||||||
// how much to we pitch towards the target
|
// how much to we pitch towards the target
|
||||||
#ifndef PITCH_MAX
|
#ifndef PITCH_MAX
|
||||||
# define PITCH_MAX 25 // degrees
|
# define PITCH_MAX 15 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -370,7 +370,7 @@
|
||||||
# define NAV_D 0.00 // should always be 0
|
# define NAV_D 0.00 // should always be 0
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_IMAX
|
#ifndef NAV_IMAX
|
||||||
# define NAV_IMAX 250 // 250 degrees
|
# define NAV_IMAX 250 // 250 Lat and Longtitude
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue