mirror of https://github.com/ArduPilot/ardupilot
Copter: Move CH7 - CH8 check from read_aux_switches() to pre_arm_checks.
Moving this to pre-arm checks save some processing time and is safer.
This commit is contained in:
parent
f3a2db195e
commit
bf6120d8b7
|
@ -61,11 +61,6 @@ static void read_aux_switches()
|
|||
do_aux_switch_function(g.ch7_option, ap_system.CH7_flag);
|
||||
}
|
||||
|
||||
// safety check to ensure we ch7 and ch8 have different functions
|
||||
if (g.ch7_option == g.ch8_option) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check if ch8 switch has changed position
|
||||
if (ap_system.CH8_flag != (g.rc_8.radio_in >= AUX_SWITCH_PWM_TRIGGER)) {
|
||||
// set the ch8 flag
|
||||
|
|
|
@ -221,6 +221,14 @@ static void pre_arm_checks(bool display_failure)
|
|||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// pre-arm check to ensure ch7 and ch8 have different functions
|
||||
if (g.ch7_option == g.ch8_option) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check CH7 and CH8 settings"));
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// check accelerometers have been calibrated
|
||||
if(!ins.calibrated()) {
|
||||
|
|
Loading…
Reference in New Issue