mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter - CH6 tuning - changed Roll/Pitch Rate D tuning to use the user supplied tuning range instead of the range / 100.
also changed heli_ext_gyro_gain to make it use the tuning range directly.
This commit is contained in:
parent
e0bb7e2777
commit
75d7308fb4
@ -2024,7 +2024,6 @@ static void tuning(){
|
||||
break;
|
||||
|
||||
case CH6_RATE_KD:
|
||||
tuning_value = (float)g.rc_6.control_in / 100000.0;
|
||||
g.pid_rate_roll.kD(tuning_value);
|
||||
g.pid_rate_pitch.kD(tuning_value);
|
||||
break;
|
||||
@ -2127,7 +2126,7 @@ static void tuning(){
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
case CH6_HELI_EXTERNAL_GYRO:
|
||||
g.heli_ext_gyro_gain = tuning_value * 1000;
|
||||
g.heli_ext_gyro_gain = tuning_value;
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user