Copter: flexible CH6 declination tuning range

This commit is contained in:
Randy Mackay 2013-05-13 23:37:30 +09:00
parent 6ba9431be4
commit 319f3ef560

View File

@ -2160,7 +2160,7 @@ static void tuning(){
case CH6_DECLINATION:
// set declination to +-20degrees
compass.set_declination(ToRad(20-g.rc_6.control_in/25), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
compass.set_declination(ToRad((2.0f * g.rc_6.control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
break;
case CH6_CIRCLE_RATE: