2015-03-08 14:48:30 +01:00
/****************************************************************************
2015-04-19 13:57:07 +02:00
*
* Copyright ( c ) 2012 - 2015 PX4 Development Team . All rights reserved .
*
* Redistribution and use in source and binary forms , with or without
* modification , are permitted provided that the following conditions
* are met :
*
* 1. Redistributions of source code must retain the above copyright
* notice , this list of conditions and the following disclaimer .
* 2. Redistributions in binary form must reproduce the above copyright
* notice , this list of conditions and the following disclaimer in
* the documentation and / or other materials provided with the
* distribution .
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission .
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* " AS IS " AND ANY EXPRESS OR IMPLIED WARRANTIES , INCLUDING , BUT NOT
* LIMITED TO , THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED . IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT , INDIRECT ,
* INCIDENTAL , SPECIAL , EXEMPLARY , OR CONSEQUENTIAL DAMAGES ( INCLUDING ,
* BUT NOT LIMITED TO , PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES ; LOSS
* OF USE , DATA , OR PROFITS ; OR BUSINESS INTERRUPTION ) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY , WHETHER IN CONTRACT , STRICT
* LIABILITY , OR TORT ( INCLUDING NEGLIGENCE OR OTHERWISE ) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE , EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2015-03-08 14:48:30 +01:00
/**
2015-04-19 13:57:07 +02:00
* @ file PreflightCheck . cpp
*
* Preflight check for main system components
*
* @ author Lorenz Meier < lorenz @ px4 . io >
* @ author Johan Jansen < jnsn . johan @ gmail . com >
*/
2015-03-08 14:48:30 +01:00
2015-04-20 12:04:46 -07:00
# include <px4_config.h>
2015-04-24 11:45:14 -07:00
# include <px4_posix.h>
2015-03-08 14:48:30 +01:00
# include <unistd.h>
# include <stdlib.h>
# include <stdio.h>
# include <string.h>
# include <fcntl.h>
# include <errno.h>
# include <math.h>
2015-05-14 20:59:23 +02:00
# include <poll.h>
2015-03-08 14:48:30 +01:00
# include <systemlib/err.h>
# include <systemlib/param/param.h>
# include <systemlib/rc_check.h>
2016-03-15 18:25:02 +00:00
# include <systemlib/mavlink_log.h>
2015-03-08 14:48:30 +01:00
# include <drivers/drv_hrt.h>
# include <drivers/drv_mag.h>
# include <drivers/drv_gyro.h>
# include <drivers/drv_accel.h>
# include <drivers/drv_baro.h>
2015-04-19 23:07:32 +02:00
# include <drivers/drv_airspeed.h>
# include <uORB/topics/airspeed.h>
2015-05-14 19:19:30 +02:00
# include <uORB/topics/vehicle_gps_position.h>
2016-11-13 09:32:17 +11:00
# include <uORB/topics/estimator_status.h>
# include <uORB/topics/sensor_preflight.h>
2015-03-08 14:48:30 +01:00
# include "PreflightCheck.h"
2015-11-18 11:58:21 -08:00
# include "DevMgr.hpp"
using namespace DriverFramework ;
2015-03-08 14:48:30 +01:00
namespace Commander
{
2015-09-27 13:37:56 +02:00
2015-11-18 11:58:21 -08:00
static int check_calibration ( DevHandle & h , const char * param_template , int & devid )
2015-09-27 13:37:56 +02:00
{
bool calibration_found ;
/* new style: ask device for calibration state */
2015-11-18 11:58:21 -08:00
int ret = h . ioctl ( SENSORIOCCALTEST , 0 ) ;
2015-09-27 13:37:56 +02:00
calibration_found = ( ret = = OK ) ;
2016-03-15 18:25:02 +00:00
2015-11-18 11:58:21 -08:00
devid = h . ioctl ( DEVIOCGDEVICEID , 0 ) ;
2015-09-27 13:37:56 +02:00
2015-10-06 19:44:17 +02:00
char s [ 20 ] ;
int instance = 0 ;
2015-10-14 20:02:02 +02:00
/* old style transition: check param values */
2015-09-27 13:37:56 +02:00
while ( ! calibration_found ) {
sprintf ( s , param_template , instance ) ;
param_t parm = param_find ( s ) ;
/* if the calibration param is not present, abort */
if ( parm = = PARAM_INVALID ) {
break ;
}
/* if param get succeeds */
int calibration_devid ;
if ( ! param_get ( parm , & ( calibration_devid ) ) ) {
/* if the devid matches, exit early */
if ( devid = = calibration_devid ) {
calibration_found = true ;
break ;
}
}
2015-10-06 19:44:17 +02:00
instance + + ;
2015-09-27 13:37:56 +02:00
}
return ! calibration_found ;
}
2016-03-15 18:25:02 +00:00
static bool magnometerCheck ( orb_advert_t * mavlink_log_pub , unsigned instance , bool optional , int & device_id , bool report_fail )
2015-04-19 13:57:07 +02:00
{
bool success = true ;
char s [ 30 ] ;
sprintf ( s , " %s%u " , MAG_BASE_DEVICE_PATH , instance ) ;
2015-11-18 11:58:21 -08:00
DevHandle h ;
DevMgr : : getHandle ( s , h ) ;
2015-04-19 13:57:07 +02:00
2015-11-18 11:58:21 -08:00
if ( ! h . isValid ( ) ) {
2015-04-19 13:57:07 +02:00
if ( ! optional ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: NO MAG SENSOR #%u " , instance ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 13:57:07 +02:00
}
return false ;
}
2015-11-18 11:58:21 -08:00
int ret = check_calibration ( h , " CAL_MAG%u_ID " , device_id ) ;
2015-04-19 13:57:07 +02:00
2015-09-27 13:37:56 +02:00
if ( ret ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: MAG #%u UNCALIBRATED " , instance ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 13:57:07 +02:00
success = false ;
goto out ;
}
2015-11-18 11:58:21 -08:00
ret = h . ioctl ( MAGIOCSELFTEST , 0 ) ;
2015-04-19 13:57:07 +02:00
if ( ret ! = OK ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: MAG #%u SELFTEST FAILED " , instance ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 13:57:07 +02:00
success = false ;
goto out ;
}
out :
2015-11-18 11:58:21 -08:00
DevMgr : : releaseHandle ( h ) ;
2015-04-19 13:57:07 +02:00
return success ;
}
2016-11-13 09:32:17 +11:00
static bool imuConsistencyCheck ( orb_advert_t * mavlink_log_pub , bool checkAcc , bool checkGyro , bool report_status )
{
// get the sensor preflight data
int sensors_sub = orb_subscribe ( ORB_ID ( sensor_preflight ) ) ;
struct sensor_preflight_s sensors = { } ;
orb_copy ( ORB_ID ( sensor_preflight ) , sensors_sub , & sensors ) ;
px4_close ( sensors_sub ) ;
// Use the difference between IMU's to detect a bad calibration. If a single IMU is fitted, the value being checked will be zero so this check will always pass.
bool success = true ;
float test_limit ;
param_get ( param_find ( " COM_ARM_IMU_ACC " ) , & test_limit ) ;
if ( checkAcc ) {
if ( sensors . accel_inconsistency_m_s_s > test_limit ) {
if ( report_status ) {
2016-12-26 14:03:10 +01:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: ACCELS INCONSISTENT - CHECK CAL " ) ;
2016-11-13 09:32:17 +11:00
}
success = false ;
goto out ;
} else if ( sensors . accel_inconsistency_m_s_s > test_limit * 0.5f ) {
if ( report_status ) {
2016-12-26 14:03:10 +01:00
mavlink_log_info ( mavlink_log_pub , " PREFLIGHT ADVICE: ACCELS INCONSISTENT - CHECK CAL " ) ;
2016-11-13 09:32:17 +11:00
}
}
}
// Fail if gyro difference greater than 5 deg/sec and notify if greater than 2.5 deg/sec
param_get ( param_find ( " COM_ARM_IMU_GYR " ) , & test_limit ) ;
if ( checkGyro ) {
if ( sensors . gyro_inconsistency_rad_s > test_limit ) {
if ( report_status ) {
2016-12-26 14:03:10 +01:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: GYROS INCONSISTENT - CHECK CAL " ) ;
2016-11-13 09:32:17 +11:00
}
success = false ;
goto out ;
} else if ( sensors . gyro_inconsistency_rad_s > test_limit * 0.5f ) {
if ( report_status ) {
2016-12-26 14:03:10 +01:00
mavlink_log_info ( mavlink_log_pub , " PREFLIGHT ADVICE: GYROS INCONSISTENT - CHECK CAL " ) ;
2016-11-13 09:32:17 +11:00
}
}
}
out :
return success ;
}
2016-03-15 18:25:02 +00:00
static bool accelerometerCheck ( orb_advert_t * mavlink_log_pub , unsigned instance , bool optional , bool dynamic , int & device_id , bool report_fail )
2015-04-19 13:57:07 +02:00
{
bool success = true ;
char s [ 30 ] ;
sprintf ( s , " %s%u " , ACCEL_BASE_DEVICE_PATH , instance ) ;
2015-11-18 11:58:21 -08:00
DevHandle h ;
DevMgr : : getHandle ( s , h ) ;
2015-04-19 13:57:07 +02:00
2015-11-18 11:58:21 -08:00
if ( ! h . isValid ( ) ) {
2015-04-19 13:57:07 +02:00
if ( ! optional ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: NO ACCEL SENSOR #%u " , instance ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 13:57:07 +02:00
}
return false ;
}
2015-11-18 11:58:21 -08:00
int ret = check_calibration ( h , " CAL_ACC%u_ID " , device_id ) ;
2015-04-19 13:57:07 +02:00
2015-09-27 13:37:56 +02:00
if ( ret ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: ACCEL #%u UNCALIBRATED " , instance ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 13:57:07 +02:00
success = false ;
goto out ;
}
2015-11-18 11:58:21 -08:00
ret = h . ioctl ( ACCELIOCSELFTEST , 0 ) ;
2015-04-19 13:57:07 +02:00
if ( ret ! = OK ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: ACCEL #%u TEST FAILED: %d " , instance , ret ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 13:57:07 +02:00
success = false ;
goto out ;
}
2015-07-01 19:54:17 -07:00
# ifdef __PX4_NUTTX
2015-04-19 23:07:32 +02:00
if ( dynamic ) {
/* check measurement result range */
struct accel_report acc ;
2015-11-18 20:14:48 -08:00
ret = h . read ( & acc , sizeof ( acc ) ) ;
2015-04-19 23:07:32 +02:00
if ( ret = = sizeof ( acc ) ) {
/* evaluate values */
float accel_magnitude = sqrtf ( acc . x * acc . x + acc . y * acc . y + acc . z * acc . z ) ;
if ( accel_magnitude < 4.0f | | accel_magnitude > 15.0f /* m/s^2 */ ) {
2015-11-19 18:28:16 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: ACCEL RANGE, hold still on arming " ) ;
2015-11-19 18:28:16 +01:00
}
2015-04-19 23:07:32 +02:00
/* this is frickin' fatal */
success = false ;
goto out ;
}
} else {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: ACCEL READ " ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 23:07:32 +02:00
/* this is frickin' fatal */
success = false ;
goto out ;
}
}
2015-07-01 19:54:17 -07:00
# endif
2015-04-19 23:07:32 +02:00
2015-04-19 13:57:07 +02:00
out :
2015-11-18 20:14:48 -08:00
DevMgr : : releaseHandle ( h ) ;
2015-04-19 13:57:07 +02:00
return success ;
}
2016-03-15 18:25:02 +00:00
static bool gyroCheck ( orb_advert_t * mavlink_log_pub , unsigned instance , bool optional , int & device_id , bool report_fail )
2015-04-19 13:57:07 +02:00
{
bool success = true ;
char s [ 30 ] ;
sprintf ( s , " %s%u " , GYRO_BASE_DEVICE_PATH , instance ) ;
2015-11-18 11:58:21 -08:00
DevHandle h ;
DevMgr : : getHandle ( s , h ) ;
2015-04-19 13:57:07 +02:00
2015-11-18 11:58:21 -08:00
if ( ! h . isValid ( ) ) {
2015-04-19 13:57:07 +02:00
if ( ! optional ) {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: NO GYRO SENSOR #%u " , instance ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 13:57:07 +02:00
}
return false ;
}
2015-11-18 11:58:21 -08:00
int ret = check_calibration ( h , " CAL_GYRO%u_ID " , device_id ) ;
2015-04-19 13:57:07 +02:00
2015-09-27 13:37:56 +02:00
if ( ret ) {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: GYRO #%u UNCALIBRATED " , instance ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 13:57:07 +02:00
success = false ;
goto out ;
}
2015-11-18 11:58:21 -08:00
ret = h . ioctl ( GYROIOCSELFTEST , 0 ) ;
2015-04-19 13:57:07 +02:00
if ( ret ! = OK ) {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: GYRO #%u SELFTEST FAILED " , instance ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 13:57:07 +02:00
success = false ;
goto out ;
}
out :
2015-11-18 11:58:21 -08:00
DevMgr : : releaseHandle ( h ) ;
2015-04-19 13:57:07 +02:00
return success ;
}
2016-03-15 18:25:02 +00:00
static bool baroCheck ( orb_advert_t * mavlink_log_pub , unsigned instance , bool optional , int & device_id , bool report_fail )
2015-04-19 13:57:07 +02:00
{
bool success = true ;
char s [ 30 ] ;
sprintf ( s , " %s%u " , BARO_BASE_DEVICE_PATH , instance ) ;
2015-11-18 11:58:21 -08:00
DevHandle h ;
DevMgr : : getHandle ( s , h ) ;
2015-04-19 13:57:07 +02:00
2015-11-18 11:58:21 -08:00
if ( ! h . isValid ( ) ) {
2015-04-19 13:57:07 +02:00
if ( ! optional ) {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: NO BARO SENSOR #%u " , instance ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 13:57:07 +02:00
}
return false ;
}
2015-10-14 20:02:02 +02:00
device_id = - 1000 ;
2015-10-06 19:44:17 +02:00
// TODO: There is no baro calibration yet, since no external baros exist
// int ret = check_calibration(fd, "CAL_BARO%u_ID");
// if (ret) {
2016-09-20 12:56:08 +02:00
// mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: BARO #%u UNCALIBRATED", instance);
2015-10-06 19:44:17 +02:00
// success = false;
// goto out;
// }
//out:
2015-11-18 11:58:21 -08:00
DevMgr : : releaseHandle ( h ) ;
2015-04-19 13:57:07 +02:00
return success ;
}
2016-11-14 00:15:20 +01:00
static bool airspeedCheck ( orb_advert_t * mavlink_log_pub , bool optional , bool report_fail , bool prearm , hrt_abstime time_since_boot )
2015-04-19 23:07:32 +02:00
{
bool success = true ;
int ret ;
int fd = orb_subscribe ( ORB_ID ( airspeed ) ) ;
struct airspeed_s airspeed ;
if ( ( ret = orb_copy ( ORB_ID ( airspeed ) , fd , & airspeed ) ) | |
( hrt_elapsed_time ( & airspeed . timestamp ) > ( 500 * 1000 ) ) ) {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: AIRSPEED SENSOR MISSING " ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 23:07:32 +02:00
success = false ;
goto out ;
}
2016-02-18 09:32:44 +01:00
if ( fabsf ( airspeed . confidence ) < 0.99f ) {
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: AIRSPEED SENSOR COMM ERROR " ) ;
2016-02-18 09:32:44 +01:00
}
success = false ;
goto out ;
}
2016-11-14 00:15:20 +01:00
/**
* Check if differential pressure is off by more than 15 Pa which equals to 5 m / s when measuring no airspeed .
* Negative and positive offsets are considered . Do not check anymore while arming because pitot cover
* might have been removed .
*/
if ( time_since_boot < 1e6 ) {
// the airspeed driver filter doesn't deliver the actual value yet
success = false ;
goto out ;
}
if ( fabsf ( airspeed . differential_pressure_filtered_pa ) > 15.0f & & ! prearm ) {
2015-11-14 15:02:56 +01:00
if ( report_fail ) {
2016-11-24 11:04:11 +01:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: HIGH AIRSPEED, CHECK CALIBRATION " ) ;
2015-11-14 15:02:56 +01:00
}
2016-11-14 00:15:20 +01:00
success = false ;
goto out ;
2015-04-19 23:07:32 +02:00
}
out :
2015-07-01 11:05:45 -07:00
px4_close ( fd ) ;
2015-04-19 23:07:32 +02:00
return success ;
}
2016-03-15 18:25:02 +00:00
static bool gnssCheck ( orb_advert_t * mavlink_log_pub , bool report_fail )
2015-05-14 19:19:30 +02:00
{
bool success = true ;
2015-05-14 20:59:23 +02:00
2015-05-14 19:19:30 +02:00
int gpsSub = orb_subscribe ( ORB_ID ( vehicle_gps_position ) ) ;
2015-05-18 12:49:53 +02:00
//Wait up to 2000ms to allow the driver to detect a GNSS receiver module
2015-07-01 11:05:45 -07:00
px4_pollfd_struct_t fds [ 1 ] ;
2015-05-14 20:59:23 +02:00
fds [ 0 ] . fd = gpsSub ;
fds [ 0 ] . events = POLLIN ;
2015-07-01 11:05:45 -07:00
if ( px4_poll ( fds , 1 , 2000 ) < = 0 ) {
2015-05-14 19:19:30 +02:00
success = false ;
}
2015-05-14 20:59:23 +02:00
else {
struct vehicle_gps_position_s gps ;
if ( ( OK ! = orb_copy ( ORB_ID ( vehicle_gps_position ) , gpsSub , & gps ) ) | |
2016-06-15 12:59:39 +02:00
( hrt_elapsed_time ( & gps . timestamp ) > 1000000 ) ) {
2015-05-14 20:59:23 +02:00
success = false ;
}
}
//Report failure to detect module
2015-11-14 15:02:56 +01:00
if ( ! success ) {
if ( report_fail ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: GPS RECEIVER MISSING " ) ;
2015-11-14 15:02:56 +01:00
}
2015-05-14 20:59:23 +02:00
}
2015-05-14 19:19:30 +02:00
2015-07-01 11:05:45 -07:00
px4_close ( gpsSub ) ;
2015-05-14 19:19:30 +02:00
return success ;
}
2016-11-13 09:32:17 +11:00
static bool ekf2Check ( orb_advert_t * mavlink_log_pub , bool optional , bool report_fail )
{
// Get estimator status data if available and exit with a fail recorded if not
int sub = orb_subscribe ( ORB_ID ( estimator_status ) ) ;
bool updated ;
orb_check ( sub , & updated ) ;
struct estimator_status_s status ;
orb_copy ( ORB_ID ( estimator_status ) , sub , & status ) ;
orb_unsubscribe ( sub ) ;
px4_close ( sub ) ;
bool success = true ; // start with a pass and change to a fail if any test fails
float test_limit ; // pass limit re-used for each test
// check vertical position innovation test ratio
param_get ( param_find ( " COM_ARM_EKF_HGT " ) , & test_limit ) ;
if ( status . hgt_test_ratio > test_limit ) {
if ( report_fail ) {
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: EKF HGT ERROR " ) ;
}
success = false ;
goto out ;
}
// check velocity innovation test ratio
param_get ( param_find ( " COM_ARM_EKF_VEL " ) , & test_limit ) ;
if ( status . hgt_test_ratio > test_limit ) {
if ( report_fail ) {
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: EKF VEL ERROR " ) ;
}
success = false ;
goto out ;
}
// check horizontal position innovation test ratio
param_get ( param_find ( " COM_ARM_EKF_POS " ) , & test_limit ) ;
if ( status . pos_test_ratio > test_limit ) {
if ( report_fail ) {
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: EKF HORIZ POS ERROR " ) ;
}
success = false ;
goto out ;
}
// check magnetometer innovation test ratio
param_get ( param_find ( " COM_ARM_EKF_YAW " ) , & test_limit ) ;
if ( status . mag_test_ratio > test_limit ) {
if ( report_fail ) {
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: EKF YAW ERROR " ) ;
}
success = false ;
goto out ;
}
// check accelerometer delta velocity bias estimates
2016-12-09 11:16:57 +11:00
param_get ( param_find ( " COM_ARM_EKF_AB " ) , & test_limit ) ;
2016-11-13 09:32:17 +11:00
if ( fabsf ( status . states [ 13 ] ) > test_limit | | fabsf ( status . states [ 14 ] ) > test_limit | | fabsf ( status . states [ 15 ] ) > test_limit ) {
if ( report_fail ) {
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: EKF HIGH IMU ACCEL BIAS " ) ;
}
success = false ;
goto out ;
}
// check gyro delta angle bias estimates
2016-12-09 11:16:57 +11:00
param_get ( param_find ( " COM_ARM_EKF_GB " ) , & test_limit ) ;
2016-11-13 09:32:17 +11:00
if ( fabsf ( status . states [ 10 ] ) > test_limit | | fabsf ( status . states [ 11 ] ) > test_limit | | fabsf ( status . states [ 12 ] ) > test_limit ) {
if ( report_fail ) {
mavlink_log_critical ( mavlink_log_pub , " PREFLIGHT FAIL: EKF HIGH IMU GYRO BIAS " ) ;
}
success = false ;
goto out ;
}
out :
return success ;
}
2016-03-15 18:25:02 +00:00
bool preflightCheck ( orb_advert_t * mavlink_log_pub , bool checkMag , bool checkAcc , bool checkGyro ,
2016-11-14 00:15:20 +01:00
bool checkBaro , bool checkAirspeed , bool checkRC , bool checkGNSS ,
bool checkDynamic , bool isVTOL , bool reportFailures , bool prearm , hrt_abstime time_since_boot )
2015-04-19 13:57:07 +02:00
{
2016-03-30 10:00:22 +02:00
# ifdef __PX4_QURT
// WARNING: Preflight checks are important and should be added back when
// all the sensors are supported
2016-06-01 15:39:23 +01:00
PX4_WARN ( " Preflight checks always pass on Snapdragon. " ) ;
2016-03-30 10:00:22 +02:00
return true ;
2016-09-20 08:41:10 +02:00
# elif defined(__PX4_POSIX_RPI)
PX4_WARN ( " Preflight checks always pass on RPI. " ) ;
2016-06-29 13:10:11 -04:00
return true ;
2016-10-18 15:10:37 +02:00
# elif defined(__PX4_POSIX_BEBOP)
PX4_WARN ( " Preflight checks always pass on Bebop. " ) ;
return true ;
2016-03-30 10:00:22 +02:00
# endif
2015-04-19 13:57:07 +02:00
bool failed = false ;
2015-04-19 23:07:32 +02:00
/* ---- MAG ---- */
2015-04-19 13:57:07 +02:00
if ( checkMag ) {
2015-09-27 14:13:39 +02:00
bool prime_found = false ;
int32_t prime_id = 0 ;
param_get ( param_find ( " CAL_MAG_PRIME " ) , & prime_id ) ;
2015-04-19 13:57:07 +02:00
/* check all sensors, but fail only for mandatory ones */
for ( unsigned i = 0 ; i < max_optional_mag_count ; i + + ) {
bool required = ( i < max_mandatory_mag_count ) ;
2015-10-14 20:02:02 +02:00
int device_id = - 1 ;
2015-04-19 13:57:07 +02:00
2016-03-15 18:25:02 +00:00
if ( ! magnometerCheck ( mavlink_log_pub , i , ! required , device_id , reportFailures ) & & required ) {
2015-04-19 13:57:07 +02:00
failed = true ;
}
2015-09-27 14:13:39 +02:00
if ( device_id = = prime_id ) {
prime_found = true ;
}
}
/* check if the primary device is present */
2015-10-14 20:02:02 +02:00
if ( ! prime_found & & prime_id ! = 0 ) {
2015-11-14 15:02:56 +01:00
if ( reportFailures ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " Warning: Primary compass not found " ) ;
2015-11-14 15:02:56 +01:00
}
2015-10-14 20:02:02 +02:00
failed = true ;
2015-04-19 13:57:07 +02:00
}
}
2015-04-19 23:07:32 +02:00
/* ---- ACCEL ---- */
2015-04-19 13:57:07 +02:00
if ( checkAcc ) {
2015-09-27 14:13:39 +02:00
bool prime_found = false ;
int32_t prime_id = 0 ;
param_get ( param_find ( " CAL_ACC_PRIME " ) , & prime_id ) ;
2015-04-19 13:57:07 +02:00
/* check all sensors, but fail only for mandatory ones */
for ( unsigned i = 0 ; i < max_optional_accel_count ; i + + ) {
bool required = ( i < max_mandatory_accel_count ) ;
2015-10-14 20:02:02 +02:00
int device_id = - 1 ;
2015-04-19 13:57:07 +02:00
2016-03-15 18:25:02 +00:00
if ( ! accelerometerCheck ( mavlink_log_pub , i , ! required , checkDynamic , device_id , reportFailures ) & & required ) {
2015-04-19 13:57:07 +02:00
failed = true ;
}
2015-09-27 14:13:39 +02:00
if ( device_id = = prime_id ) {
prime_found = true ;
}
}
/* check if the primary device is present */
2015-10-14 20:02:02 +02:00
if ( ! prime_found & & prime_id ! = 0 ) {
2015-11-14 15:02:56 +01:00
if ( reportFailures ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " Warning: Primary accelerometer not found " ) ;
2015-11-14 15:02:56 +01:00
}
2015-10-14 20:02:02 +02:00
failed = true ;
2015-04-19 13:57:07 +02:00
}
}
2015-04-19 23:07:32 +02:00
/* ---- GYRO ---- */
2015-04-19 13:57:07 +02:00
if ( checkGyro ) {
2015-09-27 14:13:39 +02:00
bool prime_found = false ;
int32_t prime_id = 0 ;
param_get ( param_find ( " CAL_GYRO_PRIME " ) , & prime_id ) ;
2015-04-19 13:57:07 +02:00
/* check all sensors, but fail only for mandatory ones */
for ( unsigned i = 0 ; i < max_optional_gyro_count ; i + + ) {
bool required = ( i < max_mandatory_gyro_count ) ;
2015-10-14 20:02:02 +02:00
int device_id = - 1 ;
2015-04-19 13:57:07 +02:00
2016-03-15 18:25:02 +00:00
if ( ! gyroCheck ( mavlink_log_pub , i , ! required , device_id , reportFailures ) & & required ) {
2015-04-19 13:57:07 +02:00
failed = true ;
}
2015-09-27 14:13:39 +02:00
if ( device_id = = prime_id ) {
prime_found = true ;
}
}
/* check if the primary device is present */
2015-10-14 20:02:02 +02:00
if ( ! prime_found & & prime_id ! = 0 ) {
2015-11-14 15:02:56 +01:00
if ( reportFailures ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " Warning: Primary gyro not found " ) ;
2015-11-14 15:02:56 +01:00
}
2015-10-14 20:02:02 +02:00
failed = true ;
2015-04-19 13:57:07 +02:00
}
}
2015-04-19 23:07:32 +02:00
/* ---- BARO ---- */
2015-04-19 13:57:07 +02:00
if ( checkBaro ) {
2015-09-27 14:13:39 +02:00
bool prime_found = false ;
int32_t prime_id = 0 ;
param_get ( param_find ( " CAL_BARO_PRIME " ) , & prime_id ) ;
2015-04-19 13:57:07 +02:00
/* check all sensors, but fail only for mandatory ones */
for ( unsigned i = 0 ; i < max_optional_baro_count ; i + + ) {
bool required = ( i < max_mandatory_baro_count ) ;
2015-10-14 20:02:02 +02:00
int device_id = - 1 ;
2015-04-19 13:57:07 +02:00
2016-03-15 18:25:02 +00:00
if ( ! baroCheck ( mavlink_log_pub , i , ! required , device_id , reportFailures ) & & required ) {
2015-04-19 13:57:07 +02:00
failed = true ;
}
2015-09-27 14:13:39 +02:00
if ( device_id = = prime_id ) {
prime_found = true ;
}
2015-04-19 13:57:07 +02:00
}
2015-09-27 14:13:39 +02:00
// TODO there is no logic in place to calibrate the primary baro yet
2016-03-15 18:25:02 +00:00
// // check if the primary device is present
2015-10-14 20:02:02 +02:00
if ( ! prime_found & & prime_id ! = 0 ) {
2015-11-14 15:02:56 +01:00
if ( reportFailures ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " warning: primary barometer not operational " ) ;
2015-11-14 15:02:56 +01:00
}
2015-10-14 20:02:02 +02:00
failed = true ;
2015-10-06 19:44:17 +02:00
}
2015-04-19 13:57:07 +02:00
}
2016-11-13 09:32:17 +11:00
/* ---- IMU CONSISTENCY ---- */
imuConsistencyCheck ( mavlink_log_pub , checkAcc , checkGyro , reportFailures ) ;
2015-04-19 23:07:32 +02:00
/* ---- AIRSPEED ---- */
if ( checkAirspeed ) {
2016-11-14 00:15:20 +01:00
if ( ! airspeedCheck ( mavlink_log_pub , true , reportFailures , prearm , time_since_boot ) ) {
2015-04-19 23:07:32 +02:00
failed = true ;
}
}
/* ---- RC CALIBRATION ---- */
2015-04-19 13:57:07 +02:00
if ( checkRC ) {
2016-09-26 10:18:23 +02:00
if ( rc_calibration_check ( mavlink_log_pub , reportFailures , isVTOL ) ! = OK ) {
2015-11-14 15:02:56 +01:00
if ( reportFailures ) {
2016-09-20 12:56:08 +02:00
mavlink_log_critical ( mavlink_log_pub , " RC calibration check failed " ) ;
2015-11-14 15:02:56 +01:00
}
2015-04-19 13:57:07 +02:00
failed = true ;
}
}
2015-05-14 19:19:30 +02:00
/* ---- Global Navigation Satellite System receiver ---- */
2015-10-14 20:02:02 +02:00
if ( checkGNSS ) {
2016-03-15 18:25:02 +00:00
if ( ! gnssCheck ( mavlink_log_pub , reportFailures ) ) {
2015-05-14 19:19:30 +02:00
failed = true ;
}
}
2016-11-13 09:32:17 +11:00
/* ---- Navigation EKF ---- */
// only check EKF2 data if EKF2 is selected as the estimator and GNSS checking is enabled
int32_t estimator_type ;
param_get ( param_find ( " SYS_MC_EST_GROUP " ) , & estimator_type ) ;
if ( estimator_type = = 2 & & checkGNSS ) {
if ( ! ekf2Check ( mavlink_log_pub , true , reportFailures ) ) {
failed = true ;
}
}
2015-04-19 23:07:32 +02:00
/* Report status */
2015-04-19 13:57:07 +02:00
return ! failed ;
}
2015-04-19 23:07:32 +02:00
2015-03-08 14:48:30 +01:00
}