mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: added OSD_TYPE2 param to enable dual OSDs backend support
Co-authored-by:HWurzburg(hurzburg@yahoo.com) up to 2 OSD instances can run at the same time sharing a single OSD thread
This commit is contained in:
parent
baae1b7732
commit
3923dcb63e
|
@ -1253,20 +1253,20 @@ bool AP_Arming::camera_checks(bool display_failure)
|
|||
|
||||
bool AP_Arming::osd_checks(bool display_failure) const
|
||||
{
|
||||
#if OSD_PARAM_ENABLED && OSD_ENABLED
|
||||
if (check_enabled(ARMING_CHECK_CAMERA)) {
|
||||
#if OSD_ENABLED
|
||||
if (check_enabled(ARMING_CHECK_OSD)) {
|
||||
// if no OSD then pass
|
||||
const AP_OSD *osd = AP::osd();
|
||||
if (osd == nullptr) {
|
||||
return true;
|
||||
}
|
||||
|
||||
// check camera is ready
|
||||
// do osd checks for configuration
|
||||
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||
if (!osd->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
|
||||
check_failed(ARMING_CHECK_CAMERA, display_failure, "%s", fail_msg);
|
||||
check_failed(ARMING_CHECK_OSD, display_failure, "%s", fail_msg);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -39,6 +39,7 @@ public:
|
|||
ARMING_CHECK_AUX_AUTH = (1U << 17),
|
||||
ARMING_CHECK_VISION = (1U << 18),
|
||||
ARMING_CHECK_FFT = (1U << 19),
|
||||
ARMING_CHECK_OSD = (1U << 20),
|
||||
};
|
||||
|
||||
enum class Method {
|
||||
|
|
Loading…
Reference in New Issue