diff --git a/ArduCopter/AP_Arming_Copter.cpp b/ArduCopter/AP_Arming_Copter.cpp index 1e7bed96c8ffa..930c433ceea81 100644 --- a/ArduCopter/AP_Arming_Copter.cpp +++ b/ArduCopter/AP_Arming_Copter.cpp @@ -69,7 +69,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) } // if pre arm checks are disabled run only the mandatory checks - if (checks_to_perform == 0) { + if (should_skip_all_checks()) { return mandatory_checks(display_failure); } @@ -595,7 +595,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) } // succeed if arming checks are disabled - if (checks_to_perform == 0) { + if (should_skip_all_checks()) { return true; } @@ -653,7 +653,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) return AP_Arming::arm_checks(method); } -// mandatory checks that will be run if ARMING_CHECK is zero or arming forced +// mandatory checks that will be run if ARMING_SKIPCHK skips all or arming forced bool AP_Arming_Copter::mandatory_checks(bool display_failure) { // call mandatory gps checks and update notify status because regular gps checks will not run diff --git a/ArduCopter/AP_Arming_Copter.h b/ArduCopter/AP_Arming_Copter.h index 180525594cdb6..a9e2bb9fb6ad3 100644 --- a/ArduCopter/AP_Arming_Copter.h +++ b/ArduCopter/AP_Arming_Copter.h @@ -32,7 +32,7 @@ class AP_Arming_Copter : public AP_Arming #endif bool arm_checks(AP_Arming::Method method) override; - // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced + // mandatory checks that cannot be bypassed. This function will only be called if ARMING_SKIPCHK skips all or arming forced bool mandatory_checks(bool display_failure) override; // NOTE! the following check functions *DO* call into AP_Arming: diff --git a/ArduPlane/AP_Arming_Plane.cpp b/ArduPlane/AP_Arming_Plane.cpp index 8ce25c17a087e..e67b27f5ae295 100644 --- a/ArduPlane/AP_Arming_Plane.cpp +++ b/ArduPlane/AP_Arming_Plane.cpp @@ -55,8 +55,8 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure) check_failed(display_failure, "System not initialised"); return false; } - //are arming checks disabled? - if (checks_to_perform == 0) { + // are arming checks disabled? + if (should_skip_all_checks()) { return mandatory_checks(display_failure); } if (hal.util->was_watchdog_armed()) { @@ -258,8 +258,8 @@ bool AP_Arming_Plane::ins_checks(bool display_failure) bool AP_Arming_Plane::arm_checks(AP_Arming::Method method) { - //are arming checks disabled? - if (checks_to_perform == 0) { + // are arming checks disabled? + if (should_skip_all_checks()) { return true; } diff --git a/ArduPlane/AP_Arming_Plane.h b/ArduPlane/AP_Arming_Plane.h index b340ecdfc2f81..7d7a56d8b1264 100644 --- a/ArduPlane/AP_Arming_Plane.h +++ b/ArduPlane/AP_Arming_Plane.h @@ -33,7 +33,7 @@ class AP_Arming_Plane : public AP_Arming void update_soft_armed(); bool get_delay_arming() const { return delay_arming; }; - // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced + // mandatory checks that cannot be bypassed. This function will only be called if ARMING_SKIPCHK skips all or arming forced bool mandatory_checks(bool display_failure) override; protected: diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 9f3f00dc2e02b..6e917899abc68 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -811,7 +811,6 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" }, { Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" }, { Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" }, - { Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" }, }; void Sub::load_parameters() diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 1b7397093f4d5..445ca02d70bf0 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -418,9 +418,10 @@ extern const AP_Param::Info var_info[]; // Sub-specific default parameters static const struct AP_Param::defaults_table_struct defaults_table[] = { { "BRD_SAFETY_DEFLT", 0 }, - { "ARMING_CHECK", uint32_t(AP_Arming::Check::RC) | - uint32_t(AP_Arming::Check::VOLTAGE) | - uint32_t(AP_Arming::Check::BATTERY)}, + { "ARMING_SKIPCHK", (~(uint32_t(AP_Arming::Check::RC) | + uint32_t(AP_Arming::Check::VOLTAGE) | + uint32_t(AP_Arming::Check::BATTERY)) + ) & ((1U<<24)-1)}, // keep within float range but disable future checks { "CIRCLE_RATE", 2.0f}, { "ATC_ACCEL_Y_MAX", 110000.0f}, { "ATC_RATE_Y_MAX", 180.0f}, diff --git a/Blimp/AP_Arming_Blimp.cpp b/Blimp/AP_Arming_Blimp.cpp index d8d085389c9ef..89a4bd91df8bd 100644 --- a/Blimp/AP_Arming_Blimp.cpp +++ b/Blimp/AP_Arming_Blimp.cpp @@ -30,7 +30,7 @@ bool AP_Arming_Blimp::run_pre_arm_checks(bool display_failure) } // if pre arm checks are disabled run only the mandatory checks - if (checks_to_perform == 0) { + if (should_skip_all_checks()) { return mandatory_checks(display_failure); } @@ -266,7 +266,7 @@ bool AP_Arming_Blimp::arm_checks(AP_Arming::Method method) return AP_Arming::arm_checks(method); } -// mandatory checks that will be run if ARMING_CHECK is zero or arming forced +// mandatory checks that will be run if ARMING_SKIPCHK skips all or arming forced bool AP_Arming_Blimp::mandatory_checks(bool display_failure) { // call mandatory gps checks and update notify status because regular gps checks will not run diff --git a/Blimp/AP_Arming_Blimp.h b/Blimp/AP_Arming_Blimp.h index 168af8a46904b..6ac93d916f73b 100644 --- a/Blimp/AP_Arming_Blimp.h +++ b/Blimp/AP_Arming_Blimp.h @@ -29,7 +29,7 @@ class AP_Arming_Blimp : public AP_Arming bool pre_arm_ekf_attitude_check(); bool arm_checks(AP_Arming::Method method) override; - // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced + // mandatory checks that cannot be bypassed. This function will only be called if ARMING_SKIPCHK skips all or arming forced bool mandatory_checks(bool display_failure) override; // NOTE! the following check functions *DO* call into AP_Arming: diff --git a/Rover/AP_Arming_Rover.cpp b/Rover/AP_Arming_Rover.cpp index dc402b1611067..d978e0f65a65d 100644 --- a/Rover/AP_Arming_Rover.cpp +++ b/Rover/AP_Arming_Rover.cpp @@ -83,8 +83,8 @@ bool AP_Arming_Rover::pre_arm_checks(bool report) return false; } - //are arming checks disabled? - if (checks_to_perform == 0) { + // are arming checks disabled? + if (should_skip_all_checks()) { return mandatory_checks(report); } @@ -115,8 +115,8 @@ bool AP_Arming_Rover::arm_checks(AP_Arming::Method method) } } - //are arming checks disabled? - if (checks_to_perform == 0) { + // are arming checks disabled? + if (should_skip_all_checks()) { return true; } return AP_Arming::arm_checks(method); diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 86f70f6c45ff3..57a9c3a6f847c 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -735,7 +735,6 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_g2, 34, AP_PARAM_FLOAT, "SAIL_ANGLE_IDEAL" }, { Parameters::k_param_g2, 35, AP_PARAM_FLOAT, "SAIL_HEEL_MAX" }, { Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" }, - { Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" }, { Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" }, { Parameters::k_param_g2, 82, AP_PARAM_INT8 , "PRX1_TYPE" }, { Parameters::k_param_g2, 146, AP_PARAM_INT8 , "PRX1_ORIENT" }, diff --git a/Tools/Frame_params/Parrot_Bebop.param b/Tools/Frame_params/Parrot_Bebop.param index f5dc650f5f5c6..1f48169b65bca 100644 --- a/Tools/Frame_params/Parrot_Bebop.param +++ b/Tools/Frame_params/Parrot_Bebop.param @@ -1,5 +1,5 @@ #NOTE: Bebop default parameters (Copter-3.4 and higher) -ARMING_CHECK,126 +ARMING_SKIPCHK,2097024 ATC_ACCEL_P_MAX,220000 ATC_ACCEL_R_MAX,220000 ATC_ACCEL_Y_MAX,56000 diff --git a/Tools/Frame_params/Parrot_Bebop2.param b/Tools/Frame_params/Parrot_Bebop2.param index 621b914dc1406..908d3323db2c9 100644 --- a/Tools/Frame_params/Parrot_Bebop2.param +++ b/Tools/Frame_params/Parrot_Bebop2.param @@ -1,5 +1,5 @@ #NOTE: Bebop2 parameter defaults (Copter-3.4 and higher) -ARMING_CHECK,126 +ARMING_SKIPCHK,2097024 ATC_ACCEL_P_MAX,220000 ATC_ACCEL_R_MAX,220000 ATC_ACCEL_Y_MAX,56000 diff --git a/Tools/Frame_params/eLAB_LAB445_AC34.param b/Tools/Frame_params/eLAB_LAB445_AC34.param index ed17fe6b860d8..0976378cf1045 100644 --- a/Tools/Frame_params/eLAB_LAB445_AC34.param +++ b/Tools/Frame_params/eLAB_LAB445_AC34.param @@ -1,7 +1,7 @@ #NOTE: eLAB LAB445 Parameter defaults (Copter-3.4.6 and higher) ACRO_YAW_P,3 ANGLE_MAX,3500 -ARMING_CHECK,-10 +ARMING_SKIPCHK,8 ATC_ACCEL_P_MAX,95000.91 ATC_ACCEL_R_MAX,100000.7 ATC_ANG_PIT_P,18 diff --git a/Tools/Frame_params/intel-aero-rtf.param b/Tools/Frame_params/intel-aero-rtf.param index e3b59f5980110..34cadfc16e176 100644 --- a/Tools/Frame_params/intel-aero-rtf.param +++ b/Tools/Frame_params/intel-aero-rtf.param @@ -2,7 +2,7 @@ ACRO_YAW_P,2.5 AHRS_ORIENTATION,0 ANGLE_MAX,3000 -ARMING_CHECK,7166 +ARMING_SKIPCHK,2089984 ATC_ACCEL_P_MAX,60000 ATC_ACCEL_R_MAX,210000 ATC_ACCEL_Y_MAX,20000 diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index cc32d367bc406..5394c200a554b 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -16,6 +16,7 @@ #include #include #include +#include #include "LogReader.h" @@ -60,7 +61,7 @@ class ReplayVehicle : public AP_Vehicle { SRV_Channels servo_channels; -protected: + AP_Arming arming; protected: diff --git a/Tools/Replay/wscript b/Tools/Replay/wscript index d4c432ab2702d..7e4fd3f71ad30 100644 --- a/Tools/Replay/wscript +++ b/Tools/Replay/wscript @@ -4,9 +4,6 @@ import boards -def configure(cfg): - cfg.env.HAL_GCS_ENABLED = 0 - def build(bld): if isinstance(bld.get_board(), boards.chibios) and bld.env['WITH_FATFS'] != '1' and bld.env['WITH_LITTLEFS'] != 1: # we need a filesystem for replay diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index ca8ddaebf938b..60ff5bbb0710a 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3898,7 +3898,8 @@ def CANGPSCopterMission(self): }) self.context_push() - self.set_parameter("ARMING_CHECK", 1 << 3) + # enable only GPS arming check during ordering test + self.set_parameter("ARMING_SKIPCHK", ~(1 << 3)) self.context_collect('STATUSTEXT') self.reboot_sitl() @@ -3972,7 +3973,7 @@ def CANGPSCopterMission(self): self.context_stop_collecting('STATUSTEXT') self.progress("############################### All GPS Order Cases Tests Passed") self.progress("############################### Test Healthy Prearm check") - self.set_parameter("ARMING_CHECK", 1) + self.set_parameter("ARMING_SKIPCHK", 0) self.stop_sup_program(instance=0) self.start_sup_program(instance=0, args="-M") self.stop_sup_program(instance=1) @@ -8949,16 +8950,6 @@ def BeaconPosition(self): }) self.reboot_sitl() - # turn off GPS arming checks. This may be considered a - # bug that we need to do this. - old_arming_check = int(self.get_parameter("ARMING_CHECK")) - if old_arming_check == 1: - old_arming_check = 1 ^ 25 - 1 - new_arming_check = int(old_arming_check) & ~(1 << 3) - self.set_parameter("ARMING_CHECK", new_arming_check) - - self.reboot_sitl() - # require_absolute=True infers a GPS is present self.wait_ready_to_arm(require_absolute=False) @@ -10984,7 +10975,7 @@ def AltEstimation(self): self.wait_gps_disable(position_vertical=True) # turn off arming checks (mandatory arming checks will still be run) - self.set_parameter("ARMING_CHECK", 0) + self.set_parameter("ARMING_SKIPCHK", -1) # delay 12 sec to allow EKF to lose altitude estimate self.delay_sim_time(12) @@ -11152,7 +11143,7 @@ def test_replay_beacon_bit(self): new_onboard_logs = sorted(self.log_list()) log_difference = [x for x in new_onboard_logs if x not in old_onboard_logs] - return log_difference[2] + return log_difference[1] # index depends on the reboots and ordering thereof in BeaconPosition! def test_replay_optical_flow_bit(self): self.set_parameters({ diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 4766393a23d15..7372b3be2dee6 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -7197,11 +7197,11 @@ def mavlink_AIRSPEED(self): self.set_parameter("SIM_ARSPD_FAIL", 0) self.fly_home_land_and_disarm() - def RudderArmingWithArmingChecksZero(self): - '''check we can't arm with rudder even if checks are disabled''' + def RudderArmingWithArmingChecksSkipped(self): + '''check we can't arm with rudder even if all checks are skipped''' self.set_parameters({ "ARMING_RUDDER": 0, - "ARMING_CHECK": 0, + "ARMING_SKIPCHK": -1, "RC4_REVERSED": 0, }) self.reboot_sitl() @@ -7909,7 +7909,7 @@ def tests1b(self): self.DO_CHANGE_ALTITUDE, self.SET_POSITION_TARGET_GLOBAL_INT_for_altitude, self.MAV_CMD_NAV_LOITER_TURNS_zero_turn, - self.RudderArmingWithArmingChecksZero, + self.RudderArmingWithArmingChecksSkipped, self.TerrainLoiterToCircle, self.FenceDoubleBreach, self.ScriptedArmingChecksApplet, diff --git a/Tools/autotest/default_params/airsim-rover.parm b/Tools/autotest/default_params/airsim-rover.parm index 4326c1a394d10..d5f6024cfe3eb 100644 --- a/Tools/autotest/default_params/airsim-rover.parm +++ b/Tools/autotest/default_params/airsim-rover.parm @@ -2,7 +2,7 @@ SERVO1_FUNCTION 26 SERVO3_FUNCTION 70 INS_GYR_CAL 0 SCHED_LOOP_RATE 50 -ARMING_CHECK 0 +ARMING_SKIPCHK -1 LOG_DISARMED 1 LOG_BITMASK 65535 CRUISE_SPEED 4.636384 diff --git a/Tools/autotest/default_params/vee-gull_005.param b/Tools/autotest/default_params/vee-gull_005.param index 60aee264cca4c..e9bf64e8142d7 100644 --- a/Tools/autotest/default_params/vee-gull_005.param +++ b/Tools/autotest/default_params/vee-gull_005.param @@ -19,7 +19,7 @@ CRUISE_ALT_FLOOR,0.00 RTL_ALTITUDE,100.00 ALT_OFFSET,0 ARMING_ACCTHRESH,0.75 -ARMING_CHECK,0 +ARMING_SKIPCHK,-1 ARMING_MIN_VOLT,0 ARMING_MIN_VOLT2,0 ARMING_REQUIRE,0 diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 66aee1ff82a18..08fb66ed972cf 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -1738,7 +1738,7 @@ def RCDisableAirspeedUse(self): "COMPASS_USE": 0, "COMPASS_USE2": 0, "COMPASS_USE3": 0, - "ARMING_CHECK": 589818, # from a logfile, disables compass + "ARMING_SKIPCHK": 1 << 2, # disables compass }) self.reboot_sitl() diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index cbfaed681d177..7564dcdf0840e 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -9944,7 +9944,7 @@ def do_prep_mag_cal_test(mavproxy, params): self.set_parameter("COMPASS_ORIENT%d" % count, 0) # Only care about compass prearm - self.set_parameter("ARMING_CHECK", 4) + self.set_parameter("ARMING_SKIPCHK", ~(1 << 2)) ################################################# def do_test_mag_cal(mavproxy, params, compass_tnumber): @@ -10770,8 +10770,8 @@ def ArmFeatures(self): '''Arm features''' # TEST ARMING/DISARM self.delay_sim_time(12) # wait for gyros/accels to be happy - if self.get_parameter("ARMING_CHECK") != 1.0 and not self.is_sub(): - raise ValueError("Arming check should be 1") + if self.get_parameter("ARMING_SKIPCHK") != 0 and not self.is_sub(): + raise ValueError("Arming skipped checks should be 0") if not self.is_sub() and not self.is_tracker(): self.set_parameter("ARMING_RUDDER", 2) # allow arm and disarm with rudder on first tests if self.is_copter(): diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 95e606807fbd9..7fa9f11ff90b4 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -116,8 +116,8 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @Param{Plane, Rover}: REQUIRE // @DisplayName: Require Arming Motors - // @Description{Plane}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, send 0 PWM (no signal) to throttle channel when disarmed. On planes with ICE enabled and the throttle while disarmed option set in ICE_OPTIONS, the motor will always get THR_MIN when disarmed. Arming will be blocked until all mandatory and ARMING_CHECK items are satisfied; arming can then be accomplished via (eg.) rudder gesture or GCS command. - // @Description{Rover}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, all checks specified by ARMING_CHECKS must pass before the vehicle can be armed (for example, via rudder stick or GCS command). If 3, Arm immediately once pre-arm/arm checks are satisfied, but only one time per boot up. Note that a reboot is NOT required when setting to 0 but IS require when setting to 3. + // @Description{Plane}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, send 0 PWM (no signal) to throttle channel when disarmed. On planes with ICE enabled and the throttle while disarmed option set in ICE_OPTIONS, the motor will always get THR_MIN when disarmed. Arming will be blocked until all mandatory and non-ARMING_SKIPCHK items are satisfied; arming can then be accomplished via (eg.) rudder gesture or GCS command. + // @Description{Rover}: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, all checks not skipped by ARMING_SKIPCHK must pass before the vehicle can be armed (for example, via rudder stick or GCS command). If 3, Arm immediately once pre-arm/arm checks are satisfied, but only one time per boot up. Note that a reboot is NOT required when setting to 0 but IS require when setting to 3. // @Values{Plane}: 0:Disabled,1:Yes(minimum PWM when disarmed),2:Yes(0 PWM when disarmed) // @Values{Rover}: 0:No,1:Yes(minimum PWM when disarmed),3:No(AutoArmOnce after checks are passed) // @User: Advanced @@ -157,13 +157,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @User: Advanced AP_GROUPINFO("MIS_ITEMS", 7, AP_Arming, _required_mission_items, 0), - // @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. For most users it is recommended to leave this at the default of 1 (all checks enabled). 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. - // @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, float(Check::ALL)), + // index 8 was CHECK stored as AP_Int32, became SKIPCHK // @Param: OPTIONS // @DisplayName: Arming options @@ -198,6 +192,14 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { AP_GROUPINFO("NEED_LOC", 12, AP_Arming, require_location, float(AP_ARMING_NEED_LOC_DEFAULT)), #endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED + // @Param: SKIPCHK + // @DisplayName: Arm Checks to Skip (bitmask) + // @Description: Checks to skip prior to arming motor. This is a bitmask of checks before allowing arming that will be skipped. For most users it is recommended to leave this at the default of 0 (no checks skipped). In extreme circumstances, a value of -1 can be used to skip all non-mandatory current and future checks. + // @Bitmask: 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}: 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("SKIPCHK", 13, AP_Arming, checks_to_skip, 0), + AP_GROUPEND }; @@ -221,6 +223,39 @@ AP_Arming::AP_Arming() AP_Param::setup_object_defaults(this, var_info); } +__INITFUNC__ void AP_Arming::init(void) +{ + // PARAM_CONVERSION - 4.7 CHECK -> SKIPCHK + + if (!checks_to_skip.configured()) { + // new parameter is not configured (though it may be set non-zero in a + // defaults table e.g. on Sub) + int32_t skipchk_new = checks_to_skip.get(); // get param default + + uint32_t idx = 8; +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + idx <<= 6; // the old index is shifted due to AP_NESTEDGROUPINFO in AP_Arming_Plane.cpp +#endif + + int32_t checks_old; + if (AP_Param::get_param_by_index(this, idx, AP_PARAM_INT32, &checks_old)) { + // the old parameter was customized + if (checks_old == 0) { // all checks disabled? + skipchk_new = -1; // skip all current and future checks + } else if (!(checks_old & 1)) { // ALL flag not set? + // mask of known checks at the time the conversion was written + uint32_t check_mask = ((1U << 21) - 1) & (~1); // remove ALL bit + // invert bits to get checks to skip + skipchk_new = (~checks_old) & check_mask; + } else { + skipchk_new = 0; // specifically enable all checks, ignoring param default + } + } + + checks_to_skip.set_and_save(skipchk_new); // set and save to finish migration + } +} + // performs pre-arm checks. expects to be called at 1hz. void AP_Arming::update(void) { @@ -281,15 +316,21 @@ bool AP_Arming::is_armed_and_safety_off() const uint32_t AP_Arming::get_enabled_checks() const { - return checks_to_perform; + // ignore unknown checks + uint32_t check_mask = (uint32_t(Check::CHECK_LAST)-1) & (~1); // remove former ALL bit + return (~checks_to_skip) & check_mask; } bool AP_Arming::check_enabled(const AP_Arming::Check check) const { - if (checks_to_perform & uint32_t(Check::ALL)) { - return true; - } - return (checks_to_perform & uint32_t(check)); + return (checks_to_skip & uint32_t(check)) == 0; +} + +bool AP_Arming::all_checks_enabled() const +{ + // ignore unknown checks + uint32_t check_mask = (uint32_t(Check::CHECK_LAST)-1) & (~1); // remove former ALL bit + return (checks_to_skip & check_mask) == 0; } void AP_Arming::check_failed(const AP_Arming::Check check, bool report, const char *fmt, ...) const @@ -1066,7 +1107,7 @@ bool AP_Arming::board_voltage_checks(bool report) #if HAL_HAVE_IMU_HEATER bool AP_Arming::heater_min_temperature_checks(bool report) { - if (checks_to_perform & uint32_t(Check::ALL)) { + if (all_checks_enabled()) { AP_BoardConfig *board = AP::boardConfig(); if (board) { float temperature; @@ -1414,7 +1455,7 @@ bool AP_Arming::fettec_checks(bool display_failure) const // check ESCs are ready char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) { - check_failed(Check::ALL, display_failure, "FETtec: %s", fail_msg); + check_failed(display_failure, "FETtec: %s", fail_msg); return false; } return true; @@ -1851,7 +1892,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) running_arming_checks = false; - if (armed && do_arming_checks && checks_to_perform == 0) { + if (armed && do_arming_checks && should_skip_all_checks()) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled"); } diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 01581c172bafe..a560140089442 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -19,10 +19,13 @@ class AP_Arming { static AP_Arming *get_singleton(); + __INITFUNC__ void init(void); + void update(); enum class Check { - ALL = (1U << 0), + // 0 used to be ALL, though it could be reused as the SKIPCHK conversion + // never sets it. check_mask would also need updating. BARO = (1U << 1), COMPASS = (1U << 2), GPS = (1U << 3), @@ -43,6 +46,7 @@ class AP_Arming { VISION = (1U << 18), FFT = (1U << 19), OSD = (1U << 20), + CHECK_LAST = (1U << 21), // must be last }; enum class Method { @@ -96,8 +100,6 @@ class AP_Arming { YES_AUTO_ARM_ZERO_PWM = 4, }; - void init(void); - // these functions should not be used by Copter which holds the armed state in the motors library Required arming_required() const; virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true); @@ -111,6 +113,10 @@ class AP_Arming { // get bitmask of enabled checks uint32_t get_enabled_checks() const; + // return if all checks are enabled, enabling all changes arming logic slightly + bool all_checks_enabled() const; + // return if all checks are set as skipped, skipping all changes arming logic slightly + bool should_skip_all_checks() const { return get_enabled_checks() == 0; } // pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass virtual bool pre_arm_checks(bool report); @@ -176,7 +182,7 @@ class AP_Arming { // Parameters AP_Enum require; - AP_Int32 checks_to_perform; // bitmask for which checks are required + AP_Int32 checks_to_skip; // bitmask for which checks should be skipped AP_Float accel_error_threshold; AP_Int8 _rudder_arming; AP_Int32 _required_mission_items; @@ -271,7 +277,7 @@ class AP_Arming { bool visodom_checks(bool report) const; bool disarm_switch_checks(bool report) const; - // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced + // mandatory checks that cannot be bypassed. This function will only be called if ARMING_SKIPCHK skips all or arming forced virtual bool mandatory_checks(bool report); // returns true if a particular check is enabled diff --git a/libraries/AP_Beacon/sitl/sitl_beacons.param b/libraries/AP_Beacon/sitl/sitl_beacons.param index fd9f93cde289a..3a9906d441097 100644 --- a/libraries/AP_Beacon/sitl/sitl_beacons.param +++ b/libraries/AP_Beacon/sitl/sitl_beacons.param @@ -1,7 +1,7 @@ # Parameters to allow use of indoor loiter with AP_Beacon library and Pozyx running IndoorLoiter2.ino and plugged into Telem2 # # disable GPS arming check -ARMING_CHECK,-9 +ARMING_SKIPCHK,8 # Set beacon origin to be approx 1.2m above ground level BCN_ALT,585.3 # the beacon origin must match the flight simulator origin - set to default SITL location (Australia) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm index 70bd0566dafea..3375a49fd9073 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm @@ -2,7 +2,7 @@ AHRS_GPS_USE,2 AHRS_ORIENTATION,6 ANGLE_MAX,4500 -ARMING_CHECK,13822 +ARMING_SKIPCHK,2083328 ATC_ACCEL_P_MAX,200000 ATC_ACCEL_R_MAX,200000 ATC_ACCEL_Y_MAX,50000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm index 7041fc2eb16b3..ab4d0ef36d431 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm @@ -107,7 +107,7 @@ FENCE_RADIUS 100 FENCE_ALT_MAX 50 # arming -ARMING_CHECK 25586 +ARMING_SKIPCHK 2071564 DISARM_DELAY 8 # IMU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm index 7c67efe2ba772..29889461b1af2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm @@ -100,7 +100,6 @@ FENCE_ALT_MAX 50 FENCE_MARGIN 3 # arming -ARMING_CHECK 32767 DISARM_DELAY 8 # IMU diff --git a/libraries/AP_HAL_ESP32/hwdef/esp32s3m5stampfly/defaults.parm b/libraries/AP_HAL_ESP32/hwdef/esp32s3m5stampfly/defaults.parm index 7bbb31c1290af..d63dcd12bf5f3 100644 --- a/libraries/AP_HAL_ESP32/hwdef/esp32s3m5stampfly/defaults.parm +++ b/libraries/AP_HAL_ESP32/hwdef/esp32s3m5stampfly/defaults.parm @@ -3,7 +3,7 @@ FRAME_CLASS 1 MOT_PWM_TYPE 3 # brushed motor PWM RC_SPEED 32000 # as fast as ardupilot supports (more would be nice) LOG_BACKEND_TYPE 2 # mavlink logging -ARMING_CHECK 1047038 # all except logging (if log rx not up) +ARMING_SKIPCHK 1024 # disable logging check (in the event log rx is not up) LOG_DISARMED 1 SCHED_LOOP_RATE 150 # flash won't go faster :( diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 512b5e2dc6d6e..a2c5e02e24f02 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1093,7 +1093,7 @@ bool AP_Param::find_top_level_key_by_pointer(const void *ptr, uint16_t &key) is used to find the old value of a parameter that has been removed from an object. */ -bool AP_Param::get_param_by_index(void *obj_ptr, uint8_t idx, ap_var_type old_ptype, void *pvalue) +bool AP_Param::get_param_by_index(void *obj_ptr, uint32_t idx, ap_var_type old_ptype, void *pvalue) { uint16_t key; if (!find_top_level_key_by_pointer(obj_ptr, key)) { diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 9a30b97ec0ad1..48bd57ab3b99d 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -521,7 +521,7 @@ class AP_Param is used to find the old value of a parameter that has been removed from an object. */ - static bool get_param_by_index(void *obj_ptr, uint8_t idx, ap_var_type old_ptype, void *pvalue); + static bool get_param_by_index(void *obj_ptr, uint32_t idx, ap_var_type old_ptype, void *pvalue); /// Erase all variables in EEPROM. /// diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 69c2db2fec4f6..2c6bfc5c42e54 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -531,6 +531,10 @@ void AP_Vehicle::setup() rpm_sensor.init(); #endif +#if AP_ARMING_ENABLED + AP::arming().init(); +#endif + // invalidate count in case an enable parameter changed during // initialisation AP_Param::invalidate_count(); diff --git a/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param b/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param index 625e2dbfd94cc..617711f4b7348 100644 --- a/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param +++ b/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param @@ -22,7 +22,7 @@ CRUISE_ALT_FLOOR,0.00 RTL_ALTITUDE,100.00 ALT_OFFSET,0 ARMING_ACCTHRESH,0.75 -ARMING_CHECK,0 +ARMING_SKIPCHK,-1 ARMING_REQUIRE,0 ARMING_RUDDER,1 ARMING_VOLT_MIN,0 diff --git a/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param b/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param index 0d7eeab9bc12d..6cc179802c9b2 100644 --- a/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param +++ b/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param @@ -22,7 +22,7 @@ CRUISE_ALT_FLOOR,0.00 RTL_ALTITUDE,100.00 ALT_OFFSET,0 ARMING_ACCTHRESH,0.75 -ARMING_CHECK,0 +ARMING_SKIPCHK,-1 ARMING_REQUIRE,0 ARMING_RUDDER,1 ARMING_VOLT_MIN,0 diff --git a/libraries/SITL/examples/Webots/quadPlus.parm b/libraries/SITL/examples/Webots/quadPlus.parm index c041a6a9c5c90..ed814390bc5cb 100644 --- a/libraries/SITL/examples/Webots/quadPlus.parm +++ b/libraries/SITL/examples/Webots/quadPlus.parm @@ -13,4 +13,4 @@ ATC_RAT_RLL_I 0.0300000 ATC_RAT_PIT_D 0.003 ATC_RAT_RLL_D 0.003 ATC_RAT_YAW_D 0.0000100 -ARMING_CHECK 33554398 +ARMING_SKIPCHK 32 diff --git a/libraries/SITL/examples/Webots/quadPlus2.parm b/libraries/SITL/examples/Webots/quadPlus2.parm index fd222c23eca5c..8837c251d8b7b 100644 --- a/libraries/SITL/examples/Webots/quadPlus2.parm +++ b/libraries/SITL/examples/Webots/quadPlus2.parm @@ -14,4 +14,4 @@ ATC_RAT_RLL_I 0.0300000 ATC_RAT_PIT_D 0.003 ATC_RAT_RLL_D 0.003 ATC_RAT_YAW_D 0.0000100 -ARMING_CHECK 33554398 +ARMING_SKIPCHK 32 diff --git a/libraries/SITL/examples/Webots/quadX.parm b/libraries/SITL/examples/Webots/quadX.parm index 7349d5361ec96..ad31fc4213109 100644 --- a/libraries/SITL/examples/Webots/quadX.parm +++ b/libraries/SITL/examples/Webots/quadX.parm @@ -13,4 +13,4 @@ ATC_RAT_RLL_I 0.0300000 ATC_RAT_PIT_D 0.003 ATC_RAT_RLL_D 0.003 ATC_RAT_YAW_D 0.0000100 -ARMING_CHECK 33554398 +ARMING_SKIPCHK 32 diff --git a/libraries/SITL/examples/Webots/quadX2.parm b/libraries/SITL/examples/Webots/quadX2.parm index 7dc8d9daf01d2..8e18d8c8ad4df 100644 --- a/libraries/SITL/examples/Webots/quadX2.parm +++ b/libraries/SITL/examples/Webots/quadX2.parm @@ -14,7 +14,7 @@ ATC_RAT_RLL_I 0.0300000 ATC_RAT_PIT_D 0.003 ATC_RAT_RLL_D 0.003 ATC_RAT_YAW_D 0.0000100 -ARMING_CHECK 33554398 +ARMING_SKIPCHK 32 SIM_WIND_DIR 90.0 SIM_WIND_SPD 5.0 SIM_WIND_TURB 0.0 diff --git a/libraries/SITL/examples/Webots_Python/params/blueboat.parm b/libraries/SITL/examples/Webots_Python/params/blueboat.parm index ede5d1985b48e..91a6b26aee858 100644 --- a/libraries/SITL/examples/Webots_Python/params/blueboat.parm +++ b/libraries/SITL/examples/Webots_Python/params/blueboat.parm @@ -6,8 +6,7 @@ SERVO3_FUNCTION 0 SERVO4_FUNCTION 0 AHRS_EKF_TYPE 10 -#ARMING_CHECK 1045534 -ARMING_CHECK 0 +ARMING_SKIPCHK -1 MOT_THST_EXPO 0 MOT_THST_HOVER 0.5 diff --git a/libraries/SITL/examples/Webots_Python/params/crazyflie.parm b/libraries/SITL/examples/Webots_Python/params/crazyflie.parm index e2431c1c9e741..1e8d6d0c98df0 100644 --- a/libraries/SITL/examples/Webots_Python/params/crazyflie.parm +++ b/libraries/SITL/examples/Webots_Python/params/crazyflie.parm @@ -17,7 +17,7 @@ ATC_RAT_RLL_D 0.0003 ATC_RAT_YAW_D 0.000001 AHRS_EKF_TYPE 10 # Use sim AHRS -ARMING_CHECK 1045534 # No RC requirements +ARMING_SKIPCHK 64 # No RC requirements MOT_THST_EXPO 0 # No motor exponential SCHED_LOOP_RATE 300 INS_GYR_CAL 0 \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/params/iris.parm b/libraries/SITL/examples/Webots_Python/params/iris.parm index f6abd7ff15b88..56adca2672e08 100644 --- a/libraries/SITL/examples/Webots_Python/params/iris.parm +++ b/libraries/SITL/examples/Webots_Python/params/iris.parm @@ -17,7 +17,7 @@ ATC_RAT_RLL_D 0.0003 ATC_RAT_YAW_D 0.000001 AHRS_EKF_TYPE 10 # Use sim AHRS -ARMING_CHECK 1045534 # No RC requirements +ARMING_SKIPCHK 64 # No RC requirements MOT_THST_EXPO 0 # No motor exponential SCHED_LOOP_RATE 300 INS_GYR_CAL 0 \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm b/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm index 558722f94526e..0507316c48328 100644 --- a/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm +++ b/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm @@ -6,7 +6,7 @@ SERVO3_FUNCTION 74 # (Throttle Right) SERVO4_FUNCTION 74 AHRS_EKF_TYPE 10 # Use sim AHRS -ARMING_CHECK 1045534 # No RC requirements +ARMING_SKIPCHK 64 # No RC requirements MOT_THST_EXPO 0 # No motor exponential SCHED_LOOP_RATE 300 INS_GYR_CAL 0 \ No newline at end of file