Skip to content
Snippets Groups Projects
Commit 114e6a35 authored by rmackay9's avatar rmackay9
Browse files

ArduCopter - combined CH6_DAMP and CH6_STABILIZE_KD tuning parameters to avoid confusion

parent c62ce957
No related branches found
No related tags found
No related merge requests found
......@@ -2043,10 +2043,6 @@ static void tuning(){
switch(g.radio_tuning){
case CH6_DAMP:
g.stabilize_d.set(tuning_value);
break;
case CH6_RATE_KD:
g.pid_rate_roll.kD(tuning_value);
g.pid_rate_pitch.kD(tuning_value);
......@@ -2062,6 +2058,7 @@ static void tuning(){
g.pi_stabilize_pitch.kI(tuning_value);
break;
case CH6_DAMP:
case CH6_STABILIZE_KD:
g.stabilize_d = tuning_value;
break;
......
......@@ -145,7 +145,7 @@
// Attitude
#define CH6_STABILIZE_KP 1
#define CH6_STABILIZE_KI 2
#define CH6_STABILIZE_KD 29
#define CH6_STABILIZE_KD 29 // duplicate with CH6_DAMP
#define CH6_YAW_KP 3
#define CH6_YAW_KI 24
// Rate
......@@ -172,7 +172,7 @@
// altitude controller
#define CH6_THR_HOLD_KP 14
#define CH6_Z_GAIN 15
#define CH6_DAMP 16
#define CH6_DAMP 16 // duplicate with CH6_YAW_RATE_KD
// optical flow controller
#define CH6_OPTFLOW_KP 17
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment