Upped some gains on Nav based on testing.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@3279 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
bb49ba1757
commit
e9cce02016
@ -475,17 +475,17 @@
|
|||||||
# define LOITER_I 0.01 //
|
# define LOITER_I 0.01 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_IMAX
|
#ifndef LOITER_IMAX
|
||||||
# define LOITER_IMAX 8 // degrees°
|
# define LOITER_IMAX 12 // degrees°
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef NAV_P
|
#ifndef NAV_P
|
||||||
# define NAV_P 2.4 // for 4.5 ms error = 13.5 pitch
|
# define NAV_P 2.0 // for 4.5 ms error = 13.5 pitch
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_I
|
#ifndef NAV_I
|
||||||
# define NAV_I 0.03 // this
|
# define NAV_I 0.1 // this
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_IMAX
|
#ifndef NAV_IMAX
|
||||||
# define NAV_IMAX 8 // degrees
|
# define NAV_IMAX 16 // degrees
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -505,7 +505,7 @@
|
|||||||
|
|
||||||
|
|
||||||
#ifndef WAYPOINT_SPEED_MAX
|
#ifndef WAYPOINT_SPEED_MAX
|
||||||
# define WAYPOINT_SPEED_MAX 300 // for 6m/s error = 13mph
|
# define WAYPOINT_SPEED_MAX 450 // for 6m/s error = 13mph
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user