Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
38ce279
AP_Arming: rehabilitate AP_Arming init
tpwrules Nov 22, 2025
0af2e7a
AP_Vehicle: rehabilitate AP_Arming init
tpwrules Nov 22, 2025
eb75557
Tools/Replay: remove unused configure function
tpwrules Nov 23, 2025
c775feb
Tools/Replay: add AP_Arming object to replay vehicle
tpwrules Nov 23, 2025
e1d8e7b
ArduSub: remove old ARMING_CHECK conversion
tpwrules Nov 22, 2025
c712827
Rover: remove old ARMING_CHECK conversion
tpwrules Nov 22, 2025
455d1d8
autotest: don't fiddle with ARMING_CHECK in BeaconPosition
tpwrules Nov 29, 2025
5f2ab50
AP_Param: expand `get_param_by_index` index
tpwrules Nov 29, 2025
d74770e
AP_Arming: turn ARMING_CHECK into ARMING_SKIPCHK
tpwrules Nov 29, 2025
7fbc4c3
ArduCopter: turn ARMING_CHECK into ARMING_SKIPCHK
tpwrules Nov 29, 2025
a7ebc19
ArduPlane: turn ARMING_CHECK into ARMING_SKIPCHK
tpwrules Nov 29, 2025
f24de53
ArduSub: turn ARMING_CHECK into ARMING_SKIPCHK
tpwrules Nov 29, 2025
e2ac184
Blimp: turn ARMING_CHECK into ARMING_SKIPCHK
tpwrules Nov 29, 2025
92dd130
Rover: turn ARMING_CHECK into ARMING_SKIPCHK
tpwrules Nov 29, 2025
c57b571
autotest: use ARMING_SKIPCHK
tpwrules Nov 22, 2025
af044d0
AP_HAL_ESP32: use ARMING_SKIPCHK in stampfly default params
tpwrules Nov 22, 2025
a7c2533
AP_HAL_ChibiOS: manually convert ARMING_SKIPCHK in default params
tpwrules Nov 22, 2025
fdf3c68
SITL/examples: update to use ARMING_SKIPCHK in params
tpwrules Nov 22, 2025
e923c99
Tools/Frame_params: manually convert ARMING_SKIPCHK
tpwrules Nov 22, 2025
f498b13
AP_Beacon: use ARMING_SKIPCHK in sitl params
tpwrules Nov 22, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions ArduCopter/AP_Arming_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 (all_checks_skipped()) {
return mandatory_checks(display_failure);
}

Expand Down Expand Up @@ -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 (all_checks_skipped()) {
return true;
}

Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/AP_Arming_Plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 (all_checks_skipped()) {
return mandatory_checks(display_failure);
}
if (hal.util->was_watchdog_armed()) {
Expand Down Expand Up @@ -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 (all_checks_skipped()) {
return true;
}

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/AP_Arming_Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
1 change: 0 additions & 1 deletion ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
7 changes: 4 additions & 3 deletions ArduSub/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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))
Comment on lines +422 to +423
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should actually have a closer look at these - they may be historical and no-longer-needed

You can arm Copter without RC. Adding RC in here means you can see an RC and then lose it and still be able to arm. I don't know if that's desired behaviour

The voltage/battery checks are weird, too, as there shouldn't be a battery monitor set up by default.

@Williangalvani

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would be happy to let Sub to default to all checks enabled if Willian approves.

On the other hand, doing that does break half the tests.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@peterbarker

The voltage/battery checks are weird, too, as there shouldn't be a battery monitor set up by default

We could use battery bit to allow user to skip arming voltage check (but maybe not low/critical) ex. for performing a lot of short missions on one battery.

You can arm Copter without RC. Adding RC in here means you can see an RC and then lose it and still be able to arm. I don't know if that's desired behaviour

That may be the case for some users ex. performing test hover prior to auto mission without RC control. This should would require 0-ing RC input state if it isn't seen when disarmed.

) & ((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},
Expand Down
4 changes: 2 additions & 2 deletions Blimp/AP_Arming_Blimp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 (all_checks_skipped()) {
return mandatory_checks(display_failure);
}

Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion Blimp/AP_Arming_Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
8 changes: 4 additions & 4 deletions Rover/AP_Arming_Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 (all_checks_skipped()) {
return mandatory_checks(report);
}

Expand Down Expand Up @@ -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 (all_checks_skipped()) {
return true;
}
return AP_Arming::arm_checks(method);
Expand Down
1 change: 0 additions & 1 deletion Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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" },
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/Parrot_Bebop.param
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/Parrot_Bebop2.param
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/eLAB_LAB445_AC34.param
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/Frame_params/intel-aero-rtf.param
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 2 additions & 1 deletion Tools/Replay/Replay.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Vehicle/AP_FixedWing.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_Arming/AP_Arming.h>

#include "LogReader.h"

Expand Down Expand Up @@ -60,7 +61,7 @@ class ReplayVehicle : public AP_Vehicle {

SRV_Channels servo_channels;

protected:
AP_Arming arming;

protected:

Expand Down
3 changes: 0 additions & 3 deletions Tools/Replay/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
19 changes: 5 additions & 14 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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)

Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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({
Expand Down
8 changes: 4 additions & 4 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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,
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/airsim-rover.parm
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/vee-gull_005.param
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
6 changes: 3 additions & 3 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down Expand Up @@ -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():
Expand Down
Loading
Loading