Browse Source

Copter: pre-arm check of throttle failsafe value

Check throttle min is above throttle failsafe trigger and that trigger
is above ppm encoder's loss-of-signal value of 900
mission-4.1.18
Randy Mackay 12 years ago
parent
commit
213472102c
  1. 11
      ArduCopter/motors.pde

11
ArduCopter/motors.pde

@ -284,6 +284,17 @@ static void pre_arm_checks(bool display_failure)
} }
#endif #endif
// failsafe parameter checks
if (g.failsafe_throttle) {
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
if (g.rc_3.radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check FS_THR_VALUE"));
}
return;
}
}
// if we've gotten this far then pre arm checks have completed // if we've gotten this far then pre arm checks have completed
ap.pre_arm_check = true; ap.pre_arm_check = true;
} }

Loading…
Cancel
Save