mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: arming check for release gripper on thrust loss
This commit is contained in:
parent
f0dff02e79
commit
d28fa49ee1
@ -278,6 +278,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_GRIPPER_ENABLED
|
||||
// check deprecated release-gripper-on-thrust-loss flight option
|
||||
if (copter.option_is_enabled(Copter::FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS_DEPRECATED)) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "FLIGHT_OPTIONS has deprecated option set");
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// check adsb avoidance failsafe
|
||||
#if HAL_ADSB_ENABLED
|
||||
if (copter.failsafe.adsb) {
|
||||
|
@ -627,7 +627,7 @@ private:
|
||||
enum class FlightOption : uint32_t {
|
||||
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
|
||||
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
|
||||
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
|
||||
RELEASE_GRIPPER_ON_THRUST_LOSS_DEPRECATED = (1<<2), // 4 (deprecated)
|
||||
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
|
||||
};
|
||||
// returns true if option is enabled for this vehicle
|
||||
|
@ -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, 3:Require position for arming
|
||||
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss (removed in 4.6+), 3:Require position for arming
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user