@ -114,10 +114,10 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
@@ -114,10 +114,10 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @Param: CHECK
// @DisplayName: Arm Checks to Perform (bitmask)
// @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. The default is no checks, allowing arming at any time. You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72. For most users it is recommended that you set this to 1 to enable all checks.
// @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration,8192:System,16384:Mission,32768:RangeFinder,65536:Camera,131072:AuxAuth
// @Values{Plane}: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration,8192:System,16384:Mission,32768:RangeFinder,65536:Camera,131072:AuxAuth
// @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,18:VisualOdometry
// @Bitmask{Plane}: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth
// @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration,8192:System,16384:Mission,32768:RangeFinder,65536:Camera,131072:AuxAuth,524288:FFT
// @Values{Plane}: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration,8192:System,16384:Mission,32768:RangeFinder,65536:Camera,131072:AuxAuth,524288:FFT
// @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,18:VisualOdometry,19:FFT
// @Bitmask{Plane}: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder,16:Camera,17:AuxAuth,19:FFT
// @User: Standard
AP_GROUPINFO ( " CHECK " , 8 , AP_Arming , checks_to_perform , ARMING_CHECK_ALL ) ,
@ -368,12 +368,18 @@ bool AP_Arming::ins_checks(bool report)
@@ -368,12 +368,18 @@ bool AP_Arming::ins_checks(bool report)
}
# if HAL_GYROFFT_ENABLED
// Check that the noise analyser works
AP_GyroFFT * fft = AP : : fft ( ) ;
if ( fft ! = nullptr & & ! fft - > calibration_check ( ) ) {
check_failed ( ARMING_CHECK_INS , report , " FFT self-test failed " ) ;
return false ;
} ;
// gyros are healthy so check the FFT
if ( ( checks_to_perform & ARMING_CHECK_ALL ) | |
( checks_to_perform & ARMING_CHECK_FFT ) ) {
// Check that the noise analyser works
AP_GyroFFT * fft = AP : : fft ( ) ;
char fail_msg [ MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN + 1 ] ;
if ( fft ! = nullptr & & ! fft - > pre_arm_check ( fail_msg , ARRAY_SIZE ( fail_msg ) ) ) {
check_failed ( ARMING_CHECK_INS , report , " %s " , fail_msg ) ;
return false ;
}
}
# endif
}
@ -1069,6 +1075,13 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
@@ -1069,6 +1075,13 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
}
}
# if HAL_GYROFFT_ENABLED
// make sure the FFT subsystem is enabled if arming checks have been disabled
AP_GyroFFT * fft = AP : : fft ( ) ;
if ( fft ! = nullptr ) {
fft - > prepare_for_arming ( ) ;
}
# endif
// ensure the GPS drivers are ready on any final changes
if ( ( checks_to_perform & ARMING_CHECK_ALL ) | |
( checks_to_perform & ARMING_CHECK_GPS_CONFIG ) ) {