mirror of https://github.com/ArduPilot/ardupilot
AP_VisualOdom: Check for driver availability first
This commit is contained in:
parent
7b8bc6b00b
commit
9bcc26046c
|
@ -258,18 +258,18 @@ bool AP_VisualOdom::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) co
|
|||
return true;
|
||||
}
|
||||
|
||||
// check healthy
|
||||
if (!healthy()) {
|
||||
hal.util->snprintf(failure_msg, failure_msg_len, "not healthy");
|
||||
return false;
|
||||
}
|
||||
|
||||
// if no backend we must have failed to create because out of memory
|
||||
if (_driver == nullptr) {
|
||||
hal.util->snprintf(failure_msg, failure_msg_len, "out of memory");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check healthy
|
||||
if (!healthy()) {
|
||||
hal.util->snprintf(failure_msg, failure_msg_len, "not healthy");
|
||||
return false;
|
||||
}
|
||||
|
||||
// call backend specific arming check
|
||||
return _driver->pre_arm_check(failure_msg, failure_msg_len);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue