mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Copter: all pre-arm checks to be disabled
set ARMING_CHECK parameter to zero to disable
This commit is contained in:
parent
43c377ca67
commit
bd44c2f73d
@ -83,7 +83,8 @@ public:
|
||||
k_param_pilot_velocity_z_max,
|
||||
k_param_circle_rate,
|
||||
k_param_sonar_gain,
|
||||
k_param_ch8_option, // 31
|
||||
k_param_ch8_option,
|
||||
k_param_arming_check_enabled, // 32
|
||||
|
||||
// 65: AP_Limits Library
|
||||
k_param_limits = 65, // deprecated - remove
|
||||
@ -339,6 +340,7 @@ public:
|
||||
AP_Int8 frame_orientation;
|
||||
AP_Int8 ch7_option;
|
||||
AP_Int8 ch8_option;
|
||||
AP_Int8 arming_check_enabled;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Heli
|
||||
|
@ -419,6 +419,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
// @Param: ARMING_CHECK
|
||||
// @DisplayName: Arming check
|
||||
// @Description: Allows enabling or disabling of pre-arming checks of receiver, accelerometer, barometer and compass
|
||||
// @Values: 0:Disabled, 1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(arming_check_enabled, "ARMING_CHECK", 1),
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
GGROUP(heli_servo_1, "HS1_", RC_Channel),
|
||||
GGROUP(heli_servo_2, "HS2_", RC_Channel),
|
||||
|
@ -191,6 +191,12 @@ static void pre_arm_checks(bool display_failure)
|
||||
return;
|
||||
}
|
||||
|
||||
// succeed if pre arm checks are disabled
|
||||
if(!g.arming_check_enabled) {
|
||||
ap.pre_arm_check = true;
|
||||
return;
|
||||
}
|
||||
|
||||
// pre-arm rc checks a prerequisite
|
||||
pre_arm_rc_checks();
|
||||
if(!ap.pre_arm_rc_check) {
|
||||
|
Loading…
Reference in New Issue
Block a user