config settings for jD motors

This commit is contained in:
Jani Hirvinen 2011-12-19 09:29:05 +07:00
parent a98a0b636a
commit 9d7eb9cd1a
2 changed files with 16 additions and 5 deletions

View File

@ -46,6 +46,7 @@
//#define RATE_ROLL_I 0.18 //#define RATE_ROLL_I 0.18
//#define RATE_PITCH_I 0.18 //#define RATE_PITCH_I 0.18
//#define MOTORS_JD880 //#define MOTORS_JD880
//#define MOTORS_JD850
// agmatthews USERHOOKS // agmatthews USERHOOKS

View File

@ -483,13 +483,23 @@
// and charachteristics changes. // and charachteristics changes.
#ifdef MOTORS_JD880 #ifdef MOTORS_JD880
# define STABILIZE_ROLL_P 3.6 # define STABILIZE_ROLL_P 3.6
# define STABILIZE_ROLL_I 0.08 # define STABILIZE_ROLL_I 0.0
# define STABILIZE_ROLL_IMAX 40.0 // degrees # define STABILIZE_ROLL_IMAX 40.0 // degrees
# define STABILIZE_PITCH_P 3.6 # define STABILIZE_PITCH_P 3.6
# define STABILIZE_PITCH_I 0.08 # define STABILIZE_PITCH_I 0.0
# define STABILIZE_PITCH_IMAX 40.0 // degrees # define STABILIZE_PITCH_IMAX 40.0 // degrees
#endif #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. // Jasons default values that are good for smaller payload motors.
#ifndef STABILIZE_ROLL_P #ifndef STABILIZE_ROLL_P
# define STABILIZE_ROLL_P 4.6 # define STABILIZE_ROLL_P 4.6