mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
Copter: pre-arm check of INS health
This commit is contained in:
parent
71bb462ad0
commit
fe822ba0b6
@ -246,6 +246,14 @@ static void pre_arm_checks(bool display_failure)
|
|||||||
return;
|
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
|
// check the compass is healthy
|
||||||
if(!compass.healthy) {
|
if(!compass.healthy) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
|
Loading…
Reference in New Issue
Block a user