ArduCopter: add Copter flight option for requiring position to arm

this is not quite the same as requiring a good position to arm.
This commit is contained in:
Peter Barker 2024-06-19 13:34:37 +10:00 committed by Peter Barker
parent 7dd50cd036
commit 180484e0a6
3 changed files with 3 additions and 2 deletions

View File

@ -444,7 +444,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif
if (mode_requires_gps) {
if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {
if (!copter.position_ok()) {
// vehicle level position estimate checks
check_failed(display_failure, "Need Position Estimate");

View File

@ -626,6 +626,7 @@ private:
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};
// returns true if option is enabled for this vehicle
bool option_is_enabled(FlightOption option) const {

View File

@ -1000,7 +1000,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
// @Description: Flight mode specific options
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),