34 #include "../PreFlightCheck.hpp" 47 const bool report_fail,
const bool prearm)
53 airspeed_sub.update();
54 const airspeed_s &airspeed = airspeed_sub.get();
57 if (report_fail && !optional) {
72 if (prearm && fabsf(airspeed.
confidence) < 0.95f) {
98 set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_DIFFPRESSURE, present, !optional, success, status);
static orb_advert_t * mavlink_log_pub
#define mavlink_log_critical(_pub, _text,...)
Send a mavlink critical message and print to console.
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)
High-resolution timer with callouts and timekeeping.
void set_health_flags(uint64_t subsystem_type, bool present, bool enabled, bool ok, vehicle_status_s &status)
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
float indicated_airspeed_m_s
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Contains helper functions to efficiently set the system health flags from commander and preflight che...