mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
config settings for jD motors
This commit is contained in:
parent
b53a6bd4b4
commit
106801a59c
@ -46,6 +46,7 @@
|
||||
//#define RATE_ROLL_I 0.18
|
||||
//#define RATE_PITCH_I 0.18
|
||||
//#define MOTORS_JD880
|
||||
//#define MOTORS_JD850
|
||||
|
||||
|
||||
// agmatthews USERHOOKS
|
||||
|
@ -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_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_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…
Reference in New Issue
Block a user