mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-14 04:38:30 -04:00
Copter: arming check that accels and gyro are healty
This commit is contained in:
parent
50e07ccad6
commit
8c0294f1b7
@ -682,6 +682,22 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
start_logging();
|
start_logging();
|
||||||
#endif
|
#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
|
// always check if inertial nav has started and is ready
|
||||||
if(!ahrs.healthy()) {
|
if(!ahrs.healthy()) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
|
Loading…
Reference in New Issue
Block a user