Skip to content

Commit

Permalink
Copter: arming check for release gripper on thrust loss
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Jul 2, 2024
1 parent 6818942 commit ea47500
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 2 deletions.
8 changes: 8 additions & 0 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -627,7 +627,7 @@ class Copter : public AP_Vehicle {
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
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),

Expand Down

0 comments on commit ea47500

Please sign in to comment.