diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 5cd0980765..ed0cba1d09 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -46,6 +46,7 @@ //#define RATE_ROLL_I 0.18 //#define RATE_PITCH_I 0.18 //#define MOTORS_JD880 +//#define MOTORS_JD850 // agmatthews USERHOOKS @@ -67,4 +68,4 @@ // #define CONFIG_APM_HARDWARE APM_HARDWARE_APM2 #define LOITER_METHOD 0 -// set to 1 to try an alternative Loiter control method \ No newline at end of file +// set to 1 to try an alternative Loiter control method diff --git a/ArduCopter/config.h b/ArduCopter/config.h index daa3456ac5..97397824a4 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -483,13 +483,23 @@ // and charachteristics changes. #ifdef MOTORS_JD880 # define STABILIZE_ROLL_P 3.6 -# define STABILIZE_ROLL_I 0.08 -# define STABILIZE_ROLL_IMAX 40.0 // degrees +# define STABILIZE_ROLL_I 0.0 +# define STABILIZE_ROLL_IMAX 40.0 // degrees # define STABILIZE_PITCH_P 3.6 -# define STABILIZE_PITCH_I 0.08 -# define STABILIZE_PITCH_IMAX 40.0 // degrees +# define STABILIZE_PITCH_I 0.0 +# define STABILIZE_PITCH_IMAX 40.0 // degrees #endif +#ifdef MOTORS_JD850 +# define STABILIZE_ROLL_P 4.0 +# define STABILIZE_ROLL_I 0.0 +# define STABILIZE_ROLL_IMAX 40.0 // degrees +# define STABILIZE_PITCH_P 4.0 +# define STABILIZE_PITCH_I 0.0 +# define STABILIZE_PITCH_IMAX 40.0 // degrees +#endif + + // Jasons default values that are good for smaller payload motors. #ifndef STABILIZE_ROLL_P # define STABILIZE_ROLL_P 4.6