Copter: add and use new allows_GCS_arming_with_throttle_high mode method

This commit is contained in:
Iampete1 2024-09-15 15:55:33 +01:00 committed by Peter Barker
parent 4894675977
commit 62a106bd4c
2 changed files with 10 additions and 1 deletions

View File

@ -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);

View File

@ -139,6 +139,9 @@ public:
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
@ -523,6 +526,9 @@ public:
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,
@ -1066,6 +1072,9 @@ public:
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