Browse Source

config settings for jD motors

master
Jani Hirvinen 13 years ago
parent
commit
106801a59c
  1. 3
      ArduCopter/APM_Config.h
  2. 18
      ArduCopter/config.h

3
ArduCopter/APM_Config.h

@ -46,6 +46,7 @@ @@ -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 @@ @@ -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
// set to 1 to try an alternative Loiter control method

18
ArduCopter/config.h

@ -483,13 +483,23 @@ @@ -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

Loading…
Cancel
Save