mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: call fettec prearm checks
This commit is contained in:
parent
4903224b47
commit
4fa548c86c
|
@ -40,6 +40,7 @@
|
||||||
#include <AP_RCMapper/AP_RCMapper.h>
|
#include <AP_RCMapper/AP_RCMapper.h>
|
||||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||||
#include <AP_OSD/AP_OSD.h>
|
#include <AP_OSD/AP_OSD.h>
|
||||||
|
#include <AP_FETtecOneWire/AP_FETtecOneWire.h>
|
||||||
|
|
||||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||||
#include <AP_CANManager/AP_CANManager.h>
|
#include <AP_CANManager/AP_CANManager.h>
|
||||||
|
@ -995,6 +996,24 @@ bool AP_Arming::osd_checks(bool display_failure) const
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Arming::fettec_checks(bool display_failure) const
|
||||||
|
{
|
||||||
|
#if HAL_AP_FETTEC_ONEWIRE_ENABLED
|
||||||
|
const AP_FETtecOneWire *f = AP_FETtecOneWire::get_singleton();
|
||||||
|
if (f == nullptr) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// check camera is ready
|
||||||
|
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||||
|
if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
|
||||||
|
check_failed(ARMING_CHECK_ALL, display_failure, "FETtec: %s", fail_msg);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed
|
// request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed
|
||||||
// returns true on success
|
// returns true on success
|
||||||
bool AP_Arming::get_aux_auth_id(uint8_t& auth_id)
|
bool AP_Arming::get_aux_auth_id(uint8_t& auth_id)
|
||||||
|
@ -1156,6 +1175,7 @@ bool AP_Arming::pre_arm_checks(bool report)
|
||||||
& proximity_checks(report)
|
& proximity_checks(report)
|
||||||
& camera_checks(report)
|
& camera_checks(report)
|
||||||
& osd_checks(report)
|
& osd_checks(report)
|
||||||
|
& fettec_checks(report)
|
||||||
& visodom_checks(report)
|
& visodom_checks(report)
|
||||||
& aux_auth_checks(report)
|
& aux_auth_checks(report)
|
||||||
& disarm_switch_checks(report)
|
& disarm_switch_checks(report)
|
||||||
|
|
|
@ -180,6 +180,8 @@ protected:
|
||||||
|
|
||||||
bool can_checks(bool report);
|
bool can_checks(bool report);
|
||||||
|
|
||||||
|
bool fettec_checks(bool display_failure) const;
|
||||||
|
|
||||||
virtual bool proximity_checks(bool report) const;
|
virtual bool proximity_checks(bool report) const;
|
||||||
|
|
||||||
bool servo_checks(bool report) const;
|
bool servo_checks(bool report) const;
|
||||||
|
|
Loading…
Reference in New Issue