Copter: arming check that accels and gyro are healty

This commit is contained in:
Randy Mackay 2015-07-29 12:19:18 +09:00
parent 45a7c37734
commit 11c9e46ec7
1 changed files with 16 additions and 0 deletions

View File

@ -682,6 +682,22 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
start_logging();
#endif
// check accels and gyro are healthy
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
if(!ins.get_accel_health_all()) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Accelerometers not healthy"));
}
return false;
}
if(!ins.get_gyro_health_all()) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Gyros not healthy"));
}
return false;
}
}
// always check if inertial nav has started and is ready
if(!ahrs.healthy()) {
if (display_failure) {