82 const bool checkGNSS,
bool reportFailures,
const bool prearm,
const hrt_abstime &time_since_boot);
97 const bool optional, int32_t &
device_id,
const bool report_fail);
100 const bool optional,
const bool dynamic, int32_t &
device_id,
const bool report_fail);
102 const bool optional, int32_t &
device_id,
const bool report_fail);
104 const bool optional, int32_t &
device_id,
const bool report_fail);
107 const bool report_fail,
const bool prearm);
112 const bool report_fail,
const bool enforce_gps_required);
static bool imuConsistencyCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_status)
static orb_advert_t * mavlink_log_pub
static struct vehicle_status_s status
static bool airspeedCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool optional, const bool report_fail, const bool prearm)
static bool magConsistencyCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_status)
static struct vehicle_status_flags_s status_flags
~PreFlightCheck()=default
static bool failureDetectorCheck(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status, const bool report_fail, const bool prearm)
static int32_t device_id[max_accel_sens]
High-resolution timer with callouts and timekeeping.
static bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, vehicle_status_flags_s &status_flags, const bool checkGNSS, bool reportFailures, const bool prearm, const hrt_abstime &time_since_boot)
Runs a preflight check on all sensors to see if they are properly calibrated and healthy.
static struct safety_s safety
static bool magnometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance, const bool optional, int32_t &device_id, const bool report_fail)
static bool gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance, const bool optional, int32_t &device_id, const bool report_fail)
static bool baroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance, const bool optional, int32_t &device_id, const bool report_fail)
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
static int rcCalibrationCheck(orb_advert_t *mavlink_log_pub, bool report_fail, bool isVTOL)
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
static bool ekf2Check(orb_advert_t *mavlink_log_pub, vehicle_status_s &vehicle_status, const bool optional, const bool report_fail, const bool enforce_gps_required)
static bool accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance, const bool optional, const bool dynamic, int32_t &device_id, const bool report_fail)
static uint8_t arm_requirements
static bool powerCheck(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status, const bool report_fail, const bool prearm)
static bool preArmCheck(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &status_flags, const safety_s &safety, const uint8_t arm_requirements)
static bool check_calibration(const char *param_template, const int32_t device_id)