Browse Source

Copter: pre-arm check of INS health

master
Randy Mackay 11 years ago
parent
commit
fe822ba0b6
  1. 8
      ArduCopter/motors.pde

8
ArduCopter/motors.pde

@ -246,6 +246,14 @@ static void pre_arm_checks(bool display_failure) @@ -246,6 +246,14 @@ static void pre_arm_checks(bool display_failure)
return;
}
// check accels and gyros are healthy
if(!ins.healthy()) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: INS not healthy"));
}
return;
}
// check the compass is healthy
if(!compass.healthy) {
if (display_failure) {

Loading…
Cancel
Save