ArduCopter - CH6 Tuning - added AHRS_YAW_KP parameter as 30. Now you can easily set the amount that the mag is used to correct the gyro based yaw estimate in the DCM

This commit is contained in:
rmackay9 2012-04-16 23:47:57 +09:00
parent 95cb35c7bb
commit 870b5e5f75
2 changed files with 6 additions and 0 deletions

View File

@ -2166,6 +2166,10 @@ static void tuning(){
g.pid_optflow_roll.kD(tuning_value);
g.pid_optflow_pitch.kD(tuning_value);
break;
case CH6_AHRS_YAW_KP:
ahrs._kp_yaw.set(tuning_value);
break;
}
}

View File

@ -184,6 +184,8 @@
#define CH6_LOITER_RATE_KI 28
#define CH6_LOITER_RATE_KD 23
#define CH6_AHRS_YAW_KP 30
// nav byte mask
// -------------