diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index a25aea6cbbe8f..e7508961534be 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -976,7 +976,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: GUID_OPTIONS // @DisplayName: Guided mode options // @Description: Options that can be applied to change guided mode behaviour - // @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw,3:SetAttitudeTarget interprets Thrust As Thrust,4:Do not stabilize PositionXY,5:Do not stabilize VelocityXY,6:Waypoint navigation used for position targets,7:Allow weathervaning + // @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw,3:SetAttitudeTarget interprets Thrust As Thrust,4:Do not stabilize PositionXY,5:Do not stabilize VelocityXY,6:Waypoint navigation used for position targets,7:Allow weathervaning,8:Require zero-throttle for arming // @User: Advanced AP_GROUPINFO("GUID_OPTIONS", 41, ParametersG2, guided_options, 0), #endif diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index fdb175f80c5b8..cd3849f222f76 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -60,6 +60,9 @@ bool RC_Channels_Copter::arming_check_throttle() const { // Copter already checks this case in its own arming checks return false; } + if (!copter.flightmode->arming_check_throttle()) { + return false; + } return RC_Channels::arming_check_throttle(); } diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 4c345a5ecaaae..90f69cbd4ef3e 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -121,6 +121,8 @@ class Mode { virtual bool requires_GPS() const = 0; virtual bool has_manual_throttle() const = 0; virtual bool allows_arming(AP_Arming::Method method) const = 0; + virtual bool arming_check_throttle() const { return true; } + virtual bool is_autopilot() const { return false; } virtual bool has_user_takeoff(bool must_navigate) const { return false; } virtual bool in_guided_mode() const { return false; } @@ -1120,6 +1122,8 @@ class ModeGuided : public Mode { bool allows_weathervaning(void) const override; #endif + bool arming_check_throttle() const override; + protected: const char *name() const override { return "GUIDED"; } @@ -1140,7 +1144,8 @@ class ModeGuided : public Mode { DoNotStabilizePositionXY = (1U << 4), DoNotStabilizeVelocityXY = (1U << 5), WPNavUsedForPosControl = (1U << 6), - AllowWeatherVaning = (1U << 7) + AllowWeatherVaning = (1U << 7), + ArmingCheckThrottle = (1U << 8), }; // returns true if the Guided-mode-option is set (see GUID_OPTIONS) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 6cf01238d0b65..6a59b4968202c 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -114,6 +114,11 @@ bool ModeGuided::allows_arming(AP_Arming::Method method) const return option_is_enabled(Option::AllowArmingFromTX); }; +bool ModeGuided::arming_check_throttle() const +{ + return option_is_enabled(Option::ArmingCheckThrottle); +} + #if WEATHERVANE_ENABLED bool ModeGuided::allows_weathervaning() const { diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 8c0605798efe8..1f65a75fee455 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -11889,6 +11889,23 @@ def ScriptingAHRSSource(self): self.set_rc(10, 2000) self.wait_statustext('Using EKF Source Set 3', check_context=True) + def GUIDEDArmingCheckThrottle(self): + '''check the way throttle is handled when arming in guided mode''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.start_subtest("With zero throttle should be able to arm") + self.arm_vehicle() + self.disarm_vehicle() + + self.start_subtest("Without option set we should be able to arm with non-zero throttle in guided") + self.set_rc(3, 1600) + self.arm_vehicle() + self.disarm_vehicle() + + self.start_subtest("With option enabled should not be able to arm with non-zero throttle") + self.set_parameter("GUID_OPTIONS", 1 << 8) + self.assert_arm_failure("is not neutral") + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ @@ -11992,6 +12009,7 @@ def tests2b(self): # this block currently around 9.5mins here self.BatteryInternalUseOnly, self.MAV_CMD_MISSION_START_p1_p2, self.ScriptingAHRSSource, + self.GUIDEDArmingCheckThrottle, ]) return ret