diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 27c3793441..c3a4f72b51 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -367,7 +367,6 @@ static const float radius_of_earth = 6378100; // meters static const float gravity = 9.81; // meters/ sec^2 static int32_t target_bearing; // deg * 100 : 0 to 360 location of the plane to the target static int32_t nav_bearing; // deg * 100 : 0 to 360 location of the plane to the target - static int32_t home_bearing; // used to track difference in angle static byte wp_control; // used to control - navgation or loiter diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 27d4eb1716..6f15346fd4 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -508,7 +508,7 @@ #ifndef STABILIZE_D -# define STABILIZE_D .25 +# define STABILIZE_D .2 #endif // Jasons default values that are good for smaller payload motors. @@ -606,17 +606,17 @@ // Navigation control gains // #ifndef LOITER_P -# define LOITER_P .2 // .3 was too aggressive +# define LOITER_P .25 // #endif #ifndef LOITER_I -# define LOITER_I 0.05 // Wind control +# define LOITER_I 0.1 // Wind control #endif #ifndef LOITER_IMAX # define LOITER_IMAX 30 // degreesĀ° #endif #ifndef NAV_P -# define NAV_P 1.5 // 3 was causing rapid oscillations in Loiter +# define NAV_P 2.2 // 3 was causing rapid oscillations in Loiter #endif #ifndef NAV_I # define NAV_I 0.15 // used in traverals @@ -649,7 +649,7 @@ // RATE control #ifndef THROTTLE_P -# define THROTTLE_P 0.4 // +# define THROTTLE_P 0.5 // #endif #ifndef THROTTLE_I # define THROTTLE_I 0.0 // @@ -663,7 +663,7 @@ // Crosstrack compensation // #ifndef CROSSTRACK_GAIN -# define CROSSTRACK_GAIN 40 +# define CROSSTRACK_GAIN 1 #endif