Copter: remove pre-arm check of RC3_TRIM
RC3_TRIM parameter is not used so we can remove this check
This commit is contained in:
parent
3edc1ea4db
commit
8b5f1575ad
@ -480,8 +480,8 @@ static void pre_arm_rc_checks()
|
||||
return;
|
||||
}
|
||||
|
||||
// check channels 3 & 4 have trim >= 1300 and <= 1700
|
||||
if (g.rc_3.radio_trim < 1300 || g.rc_3.radio_trim > 1700 || g.rc_4.radio_trim < 1300 || g.rc_4.radio_trim > 1700) {
|
||||
// check channel 4 has trim >= 1300 and <= 1700
|
||||
if (g.rc_4.radio_trim < 1300 || g.rc_4.radio_trim > 1700) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user