Skip to content

Commit

Permalink
Copter: add and use new allows_GCS_arming_with_throttle_high mode m…
Browse files Browse the repository at this point in the history
…ethod
  • Loading branch information
IamPete1 committed Sep 21, 2024
1 parent cb1a156 commit 86add22
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 1 deletion.
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -611,7 +611,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
const char *rc_item = "Throttle";
#endif
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) {
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && copter.flightmode->allows_GCS_or_SCR_arming_with_throttle_high())) {
// above top of deadband is too always high
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
Expand Down
9 changes: 9 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,9 @@ class Mode {
virtual bool allows_flip() const { return false; }
virtual bool crash_check_enabled() const { return true; }

// Return true if the throttle high arming check can be skipped when arming from GCS or Scripting
virtual bool allows_GCS_or_SCR_arming_with_throttle_high() const { return false; }

#if FRAME_CONFIG == HELI_FRAME
virtual bool allows_inverted() const { return false; };
#endif
Expand Down Expand Up @@ -509,6 +512,9 @@ class ModeAuto : public Mode {
bool allows_inverted() const override { return true; };
#endif

// Return true if the throttle high arming check can be skipped when arming from GCS or Scripting
bool allows_GCS_or_SCR_arming_with_throttle_high() const override { return true; }

// Auto modes
enum class SubMode : uint8_t {
TAKEOFF,
Expand Down Expand Up @@ -1047,6 +1053,9 @@ class ModeGuided : public Mode {

bool requires_terrain_failsafe() const override { return true; }

// Return true if the throttle high arming check can be skipped when arming from GCS or Scripting
bool allows_GCS_or_SCR_arming_with_throttle_high() const override { return true; }

// Sets guided's angular target submode: Using a rotation quaternion, angular velocity, and climbrate or thrust (depends on user option)
// attitude_quat: IF zero: ang_vel (angular velocity) must be provided even if all zeroes
// IF non-zero: attitude_control is performed using both the attitude quaternion and angular velocity
Expand Down

0 comments on commit 86add22

Please sign in to comment.