Files
ardupilot/Blimp/AP_Arming_Blimp.h
Thomas Watson 41b46bf804 Blimp: turn ARMING_CHECK into ARMING_SKIPCHK
This lowers the effort required to turn off just one arming check.
Previously, a user had to disable the ALL bit and enable every check
except the undesired one. Now they can just disable that one directly.
Hopefully this will result in less vehicles with no arming checks
whatsoever, presuming only one check is giving the user grief.

This, as a side effect, removes the difference between the ALL bit set
and all non-ALL bits set (e.g. the latter disables IMU heater checks).
It also ensures the user will get any new arming checks even if they
have skipped one.

People who need to disable all current and future checks for e.g. bench
testing can still do this efficiently by setting the parameter to `-1`,
leveraging that this sets all bits in 2s complement arithmetic.

A parameter conversion is included that skips no checks if the old ALL
bit is set; otherwise it migrates the user's selected checks. If no
checks were enabled, it disables all current and future checks.
2025-12-04 11:52:13 -06:00

58 lines
1.8 KiB
C++

#pragma once
#include <AP_Arming/AP_Arming.h>
class AP_Arming_Blimp : public AP_Arming
{
public:
friend class Blimp;
friend class ToyMode;
AP_Arming_Blimp() : AP_Arming()
{
// default REQUIRE parameter to 1 (Blimp does not have an
// actual ARMING_REQUIRE parameter)
require.set_default((uint8_t)Required::YES_MIN_PWM);
}
/* Do not allow copies */
CLASS_NO_COPY(AP_Arming_Blimp);
bool rc_calibration_checks(bool display_failure) override;
bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override;
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;
protected:
bool pre_arm_checks(bool display_failure) override;
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_SKIPCHK skips all or arming forced
bool mandatory_checks(bool display_failure) override;
// NOTE! the following check functions *DO* call into AP_Arming:
bool ins_checks(bool display_failure) override;
bool gps_checks(bool display_failure) override;
bool barometer_checks(bool display_failure) override;
bool board_voltage_checks(bool display_failure) override;
// NOTE! the following check functions *DO NOT* call into AP_Arming!
bool parameter_checks(bool display_failure);
bool motor_checks(bool display_failure);
bool oa_checks(bool display_failure);
bool mandatory_gps_checks(bool display_failure);
bool gcs_failsafe_check(bool display_failure);
bool alt_checks(bool display_failure);
void set_pre_arm_check(bool b);
private:
// actually contains the pre-arm checks. This is wrapped so that
// we can store away success/failure of the checks.
bool run_pre_arm_checks(bool display_failure);
};