PX4 Firmware
PX4 Autopilot Software http://px4.io
PreFlightCheck Class Reference

#include <PreFlightCheck.hpp>

Collaboration diagram for PreFlightCheck:

Public Types

enum  arm_requirements_t {
  ARM_REQ_NONE = 0, ARM_REQ_MISSION_BIT = (1 << 0), ARM_REQ_ARM_AUTH_BIT = (1 << 1), ARM_REQ_GPS_BIT = (1 << 2),
  ARM_REQ_ESCS_CHECK_BIT = (1 << 3)
}
 

Public Member Functions

 PreFlightCheck ()=default
 
 ~PreFlightCheck ()=default
 

Static Public Member Functions

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. More...
 
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 Private Member Functions

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 magConsistencyCheck (orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_status)
 
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 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)
 
static bool imuConsistencyCheck (orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_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 int rcCalibrationCheck (orb_advert_t *mavlink_log_pub, bool report_fail, bool isVTOL)
 
static bool powerCheck (orb_advert_t *mavlink_log_pub, const vehicle_status_s &status, const bool report_fail, const bool prearm)
 
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 failureDetectorCheck (orb_advert_t *mavlink_log_pub, const vehicle_status_s &status, const bool report_fail, const bool prearm)
 
static bool check_calibration (const char *param_template, const int32_t device_id)
 

Detailed Description

Definition at line 49 of file PreFlightCheck.hpp.

Member Enumeration Documentation

◆ arm_requirements_t

Enumerator
ARM_REQ_NONE 
ARM_REQ_MISSION_BIT 
ARM_REQ_ARM_AUTH_BIT 
ARM_REQ_GPS_BIT 
ARM_REQ_ESCS_CHECK_BIT 

Definition at line 87 of file PreFlightCheck.hpp.

Constructor & Destructor Documentation

◆ PreFlightCheck()

PreFlightCheck::PreFlightCheck ( )
default

◆ ~PreFlightCheck()

PreFlightCheck::~PreFlightCheck ( )
default

Member Function Documentation

◆ accelerometerCheck()

bool PreFlightCheck::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 
)
staticprivate

Definition at line 47 of file accelerometerCheck.cpp.

References f(), hrt_elapsed_time(), mavlink_log_critical, orb_exists(), ORB_ID, and set_health_flags().

Here is the call graph for this function:

◆ airspeedCheck()

bool PreFlightCheck::airspeedCheck ( orb_advert_t mavlink_log_pub,
vehicle_status_s status,
const bool  optional,
const bool  report_fail,
const bool  prearm 
)
staticprivate

Check if airspeed is higher than 4m/s (accepted max) while the vehicle is landed / not flying Negative and positive offsets are considered. Do not check anymore while arming because pitot cover might have been removed.

Definition at line 46 of file airspeedCheck.cpp.

References airspeed_s::confidence, hrt_elapsed_time(), airspeed_s::indicated_airspeed_m_s, mavlink_log_critical, ORB_ID, set_health_flags(), and airspeed_s::timestamp.

Here is the call graph for this function:

◆ baroCheck()

bool PreFlightCheck::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 
)
staticprivate

Definition at line 46 of file baroCheck.cpp.

References hrt_elapsed_time(), mavlink_log_critical, orb_exists(), ORB_ID, and set_health_flags().

Here is the call graph for this function:

◆ check_calibration()

bool PreFlightCheck::check_calibration ( const char *  param_template,
const int32_t  device_id 
)
staticprivate

Definition at line 341 of file PreFlightCheck.cpp.

References ll40ls::instance, param_find_no_notification(), param_get(), and PARAM_INVALID.

Here is the call graph for this function:

◆ ekf2Check()

◆ failureDetectorCheck()

bool PreFlightCheck::failureDetectorCheck ( orb_advert_t mavlink_log_pub,
const vehicle_status_s status,
const bool  report_fail,
const bool  prearm 
)
staticprivate

◆ gyroCheck()

bool PreFlightCheck::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 
)
staticprivate

Definition at line 46 of file gyroCheck.cpp.

References hrt_elapsed_time(), mavlink_log_critical, orb_exists(), ORB_ID, and set_health_flags().

Here is the call graph for this function:

◆ imuConsistencyCheck()

bool PreFlightCheck::imuConsistencyCheck ( orb_advert_t mavlink_log_pub,
vehicle_status_s status,
const bool  report_status 
)
staticprivate

Definition at line 44 of file imuConsistencyCheck.cpp.

References sensor_preflight_s::accel_inconsistency_m_s_s, sensor_preflight_s::gyro_inconsistency_rad_s, mavlink_log_critical, mavlink_log_info, ORB_ID, param_find(), param_get(), and set_health_flags_healthy().

Here is the call graph for this function:

◆ magConsistencyCheck()

bool PreFlightCheck::magConsistencyCheck ( orb_advert_t mavlink_log_pub,
vehicle_status_s status,
const bool  report_status 
)
staticprivate

Definition at line 46 of file magConsistencyCheck.cpp.

References sensor_preflight_s::mag_inconsistency_angle, mavlink_log_critical, ORB_ID, param_find(), param_get(), set_health_flags_healthy(), and sensor_preflight_s::timestamp.

Here is the call graph for this function:

◆ magnometerCheck()

bool PreFlightCheck::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 
)
staticprivate

Definition at line 46 of file magnetometerCheck.cpp.

References hrt_elapsed_time(), mavlink_log_critical, orb_exists(), ORB_ID, and set_health_flags().

Here is the call graph for this function:

◆ powerCheck()

bool PreFlightCheck::powerCheck ( orb_advert_t mavlink_log_pub,
const vehicle_status_s status,
const bool  report_fail,
const bool  prearm 
)
staticprivate

Definition at line 43 of file powerCheck.cpp.

References f(), hrt_elapsed_time(), mavlink_log_critical, ORB_ID, system_power_s::timestamp, and system_power_s::voltage5v_v.

Here is the call graph for this function:

◆ preArmCheck()

bool PreFlightCheck::preArmCheck ( orb_advert_t mavlink_log_pub,
const vehicle_status_flags_s status_flags,
const safety_s safety,
const uint8_t  arm_requirements 
)
static

◆ preflightCheck()

bool PreFlightCheck::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 
)
static

Runs a preflight check on all sensors to see if they are properly calibrated and healthy.

The function won't fail the test if optional sensors are not found, however, it will fail the test if optional sensors are found but not in working condition.

Parameters
mavlink_log_pubMavlink output orb handle reference for feedback when a sensor fails
checkMagtrue if the magneteometer should be checked
checkAcctrue if the accelerometers should be checked
checkGyrotrue if the gyroscopes should be checked
checkBarotrue if the barometer should be checked
checkAirspeedtrue if the airspeed sensor should be checked
checkRCtrue if the Remote Controller should be checked
checkGNSStrue if the GNSS receiver should be checked
checkPowertrue if the system power should be checked

Definition at line 58 of file PreFlightCheck.cpp.

References vehicle_status_flags_s::circuit_breaker_engaged_airspd_check, vehicle_status_flags_s::circuit_breaker_engaged_power_check, vehicle_status_flags_s::condition_calibration_enabled, vehicle_status_flags_s::condition_power_input_valid, vehicle_status_flags_s::condition_system_hotplug_timeout, device_id, vehicle_status_s::hil_state, vehicle_status_s::is_vtol, mavlink_log_critical, max_mandatory_accel_count, max_mandatory_baro_count, max_mandatory_gyro_count, max_mandatory_mag_count, max_optional_accel_count, max_optional_baro_count, max_optional_gyro_count, max_optional_mag_count, OK, param_find(), param_get(), vehicle_status_flags_s::rc_calibration_valid, vehicle_status_s::rc_input_mode, vehicle_status_flags_s::rc_signal_found_once, vehicle_status_s::rc_signal_lost, set_health_flags(), vehicle_status_s::vehicle_type, and VEHICLE_TYPE_FIXED_WING.

Referenced by arming_state_transition(), and Commander::preflight_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ rcCalibrationCheck()

int PreFlightCheck::rcCalibrationCheck ( orb_advert_t mavlink_log_pub,
bool  report_fail,
bool  isVTOL 
)
staticprivate

Definition at line 55 of file rcCalibrationCheck.cpp.

References mavlink_log_critical, param_find(), param_get(), PARAM_INVALID, RC_INPUT_HIGHEST_MAX_US, RC_INPUT_LOWEST_MIN_US, and RC_INPUT_MAX_DEADZONE_US.

Here is the call graph for this function:

The documentation for this class was generated from the following files: