@ -114,7 +114,7 @@ int check_calibration(int fd, const char* param_template, int &devid)
@@ -114,7 +114,7 @@ int check_calibration(int fd, const char* param_template, int &devid)
return ! calibration_found ;
}
static bool magnometerCheck ( int mavlink_fd , unsigned instance , bool optional , int & device_id )
static bool magnometerCheck ( int mavlink_fd , unsigned instance , bool optional , int & device_id , bool report_fail )
{
bool success = true ;
@ -124,7 +124,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional, in
@@ -124,7 +124,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional, in
if ( fd < 0 ) {
if ( ! optional ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: NO MAG SENSOR #%u " , instance ) ;
}
@ -134,7 +134,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional, in
@@ -134,7 +134,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional, in
int ret = check_calibration ( fd , " CAL_MAG%u_ID " , device_id ) ;
if ( ret ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: MAG #%u UNCALIBRATED " , instance ) ;
success = false ;
goto out ;
@ -143,7 +143,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional, in
@@ -143,7 +143,7 @@ static bool magnometerCheck(int mavlink_fd, unsigned instance, bool optional, in
ret = px4_ioctl ( fd , MAGIOCSELFTEST , 0 ) ;
if ( ret ! = OK ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: MAG #%u SELFTEST FAILED " , instance ) ;
success = false ;
goto out ;
@ -154,7 +154,7 @@ out:
@@ -154,7 +154,7 @@ out:
return success ;
}
static bool accelerometerCheck ( int mavlink_fd , unsigned instance , bool optional , bool dynamic , int & device_id )
static bool accelerometerCheck ( int mavlink_fd , unsigned instance , bool optional , bool dynamic , int & device_id , bool report_fail )
{
bool success = true ;
@ -164,7 +164,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
@@ -164,7 +164,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
if ( fd < 0 ) {
if ( ! optional ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: NO ACCEL SENSOR #%u " , instance ) ;
}
@ -174,7 +174,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
@@ -174,7 +174,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
int ret = check_calibration ( fd , " CAL_ACC%u_ID " , device_id ) ;
if ( ret ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: ACCEL #%u UNCALIBRATED " , instance ) ;
success = false ;
goto out ;
@ -183,7 +183,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
@@ -183,7 +183,7 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
ret = px4_ioctl ( fd , ACCELIOCSELFTEST , 0 ) ;
if ( ret ! = OK ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: ACCEL #%u SELFTEST FAILED " , instance ) ;
success = false ;
goto out ;
@ -200,13 +200,13 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
@@ -200,13 +200,13 @@ static bool accelerometerCheck(int mavlink_fd, unsigned instance, bool optional,
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 */ ) {
mavlink_and_console_log_critical ( mavlink_fd , " PREFLIGHT FAIL: ACCEL RANGE, hold still on arming " ) ;
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd , " PREFLIGHT FAIL: ACCEL RANGE, hold still on arming " ) ;
/* this is frickin' fatal */
success = false ;
goto out ;
}
} else {
mavlink_log_critical ( mavlink_fd , " PREFLIGHT FAIL: ACCEL READ " ) ;
if ( report_fail ) mavlink_log_critical ( mavlink_fd , " PREFLIGHT FAIL: ACCEL READ " ) ;
/* this is frickin' fatal */
success = false ;
goto out ;
@ -219,7 +219,7 @@ out:
@@ -219,7 +219,7 @@ out:
return success ;
}
static bool gyroCheck ( int mavlink_fd , unsigned instance , bool optional , int & device_id )
static bool gyroCheck ( int mavlink_fd , unsigned instance , bool optional , int & device_id , bool report_fail )
{
bool success = true ;
@ -229,7 +229,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
@@ -229,7 +229,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
if ( fd < 0 ) {
if ( ! optional ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: NO GYRO SENSOR #%u " , instance ) ;
}
@ -239,7 +239,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
@@ -239,7 +239,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
int ret = check_calibration ( fd , " CAL_GYRO%u_ID " , device_id ) ;
if ( ret ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: GYRO #%u UNCALIBRATED " , instance ) ;
success = false ;
goto out ;
@ -248,7 +248,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
@@ -248,7 +248,7 @@ static bool gyroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
ret = px4_ioctl ( fd , GYROIOCSELFTEST , 0 ) ;
if ( ret ! = OK ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: GYRO #%u SELFTEST FAILED " , instance ) ;
success = false ;
goto out ;
@ -259,7 +259,7 @@ out:
@@ -259,7 +259,7 @@ out:
return success ;
}
static bool baroCheck ( int mavlink_fd , unsigned instance , bool optional , int & device_id )
static bool baroCheck ( int mavlink_fd , unsigned instance , bool optional , int & device_id , bool report_fail )
{
bool success = true ;
@ -269,7 +269,7 @@ static bool baroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
@@ -269,7 +269,7 @@ static bool baroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
if ( fd < 0 ) {
if ( ! optional ) {
mavlink_and_console_log_critical ( mavlink_fd ,
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd ,
" PREFLIGHT FAIL: NO BARO SENSOR #%u " , instance ) ;
}
@ -294,7 +294,7 @@ static bool baroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
@@ -294,7 +294,7 @@ static bool baroCheck(int mavlink_fd, unsigned instance, bool optional, int &dev
return success ;
}
static bool airspeedCheck ( int mavlink_fd , bool optional )
static bool airspeedCheck ( int mavlink_fd , bool optional , bool report_fail )
{
bool success = true ;
int ret ;
@ -304,13 +304,13 @@ static bool airspeedCheck(int mavlink_fd, bool optional)
@@ -304,13 +304,13 @@ static bool airspeedCheck(int mavlink_fd, bool optional)
if ( ( ret = orb_copy ( ORB_ID ( airspeed ) , fd , & airspeed ) ) | |
( hrt_elapsed_time ( & airspeed . timestamp ) > ( 500 * 1000 ) ) ) {
mavlink_and_console_log_critical ( mavlink_fd , " PREFLIGHT FAIL: AIRSPEED SENSOR MISSING " ) ;
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd , " PREFLIGHT FAIL: AIRSPEED SENSOR MISSING " ) ;
success = false ;
goto out ;
}
if ( fabsf ( airspeed . indicated_airspeed_m_s ) > 6.0f ) {
mavlink_and_console_log_critical ( mavlink_fd , " AIRSPEED WARNING: WIND OR CALIBRATION ISSUE " ) ;
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd , " AIRSPEED WARNING: WIND OR CALIBRATION ISSUE " ) ;
// XXX do not make this fatal yet
}
@ -319,7 +319,7 @@ out:
@@ -319,7 +319,7 @@ out:
return success ;
}
static bool gnssCheck ( int mavlink_fd )
static bool gnssCheck ( int mavlink_fd , bool report_fail )
{
bool success = true ;
@ -342,7 +342,7 @@ static bool gnssCheck(int mavlink_fd)
@@ -342,7 +342,7 @@ static bool gnssCheck(int mavlink_fd)
//Report failure to detect module
if ( ! success ) {
mavlink_and_console_log_critical ( mavlink_fd , " PREFLIGHT FAIL: GPS RECEIVER MISSING " ) ;
if ( report_fail ) mavlink_and_console_log_critical ( mavlink_fd , " PREFLIGHT FAIL: GPS RECEIVER MISSING " ) ;
}
px4_close ( gpsSub ) ;
@ -350,7 +350,7 @@ static bool gnssCheck(int mavlink_fd)
@@ -350,7 +350,7 @@ static bool gnssCheck(int mavlink_fd)
}
bool preflightCheck ( int mavlink_fd , bool checkMag , bool checkAcc , bool checkGyro ,
bool checkBaro , bool checkAirspeed , bool checkRC , bool checkGNSS , bool checkDynamic )
bool checkBaro , bool checkAirspeed , bool checkRC , bool checkGNSS , bool checkDynamic , bool reportFailures )
{
bool failed = false ;
@ -365,7 +365,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -365,7 +365,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
bool required = ( i < max_mandatory_mag_count ) ;
int device_id = - 1 ;
if ( ! magnometerCheck ( mavlink_fd , i , ! required , device_id ) & & required ) {
if ( ! magnometerCheck ( mavlink_fd , i , ! required , device_id , reportFailures ) & & required ) {
failed = true ;
}
@ -376,7 +376,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -376,7 +376,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
/* check if the primary device is present */
if ( ! prime_found & & prime_id ! = 0 ) {
mavlink_log_critical ( mavlink_fd , " warning: primary compass not operational " ) ;
if ( reportFailures ) mavlink_log_critical ( mavlink_fd , " Warning: Primary compass not found " ) ;
failed = true ;
}
}
@ -392,7 +392,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -392,7 +392,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
bool required = ( i < max_mandatory_accel_count ) ;
int device_id = - 1 ;
if ( ! accelerometerCheck ( mavlink_fd , i , ! required , checkDynamic , device_id ) & & required ) {
if ( ! accelerometerCheck ( mavlink_fd , i , ! required , checkDynamic , device_id , reportFailures ) & & required ) {
failed = true ;
}
@ -403,7 +403,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -403,7 +403,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
/* check if the primary device is present */
if ( ! prime_found & & prime_id ! = 0 ) {
mavlink_log_critical ( mavlink_fd , " warning: primary accelerometer not operational " ) ;
if ( reportFailures ) mavlink_log_critical ( mavlink_fd , " Warning: Primary accelerometer not found " ) ;
failed = true ;
}
}
@ -419,7 +419,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -419,7 +419,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
bool required = ( i < max_mandatory_gyro_count ) ;
int device_id = - 1 ;
if ( ! gyroCheck ( mavlink_fd , i , ! required , device_id ) & & required ) {
if ( ! gyroCheck ( mavlink_fd , i , ! required , device_id , reportFailures ) & & required ) {
failed = true ;
}
@ -430,7 +430,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -430,7 +430,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
/* check if the primary device is present */
if ( ! prime_found & & prime_id ! = 0 ) {
mavlink_log_critical ( mavlink_fd , " warning: primary gyro not operational " ) ;
if ( reportFailures ) mavlink_log_critical ( mavlink_fd , " Warning: Primary gyro not found " ) ;
failed = true ;
}
}
@ -446,7 +446,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -446,7 +446,7 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
bool required = ( i < max_mandatory_baro_count ) ;
int device_id = - 1 ;
if ( ! baroCheck ( mavlink_fd , i , ! required , device_id ) & & required ) {
if ( ! baroCheck ( mavlink_fd , i , ! required , device_id , reportFailures ) & & required ) {
failed = true ;
}
@ -458,29 +458,29 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
@@ -458,29 +458,29 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
// TODO there is no logic in place to calibrate the primary baro yet
// // check if the primary device is present
if ( ! prime_found & & prime_id ! = 0 ) {
mavlink_log_critical ( mavlink_fd , " warning: primary barometer not operational " ) ;
if ( reportFailures ) mavlink_log_critical ( mavlink_fd , " warning: primary barometer not operational " ) ;
failed = true ;
}
}
/* ---- AIRSPEED ---- */
if ( checkAirspeed ) {
if ( ! airspeedCheck ( mavlink_fd , true ) ) {
if ( ! airspeedCheck ( mavlink_fd , true , reportFailures ) ) {
failed = true ;
}
}
/* ---- RC CALIBRATION ---- */
if ( checkRC ) {
if ( rc_calibration_check ( mavlink_fd ) ! = OK ) {
mavlink_log_critical ( mavlink_fd , " RC calibration check failed " ) ;
if ( rc_calibration_check ( mavlink_fd , reportFailures ) ! = OK ) {
if ( reportFailures ) mavlink_log_critical ( mavlink_fd , " RC calibration check failed " ) ;
failed = true ;
}
}
/* ---- Global Navigation Satellite System receiver ---- */
if ( checkGNSS ) {
if ( ! gnssCheck ( mavlink_fd ) ) {
if ( ! gnssCheck ( mavlink_fd , reportFailures ) ) {
failed = true ;
}
}