Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: add and use new allows_GCS_arming_with_throttle_high mode method #28133

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@ -139,6 +139,9 @@ class Mode {
virtual AP_AdvancedFailsafe_Copter::control_mode afs_mode() const { return AP_AdvancedFailsafe_Copter::control_mode::AFS_STABILIZED; }
#endif

// 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 @@ -523,6 +526,9 @@ class ModeAuto : public Mode {
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
#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 @@ -1066,6 +1072,9 @@ class ModeGuided : public Mode {
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
#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; }

// 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
Loading