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: remove throttle check for arming in guided #28009

Closed
Closed
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/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

Expand Down
7 changes: 6 additions & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -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; }
Expand Down Expand Up @@ -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"; }
Expand All @@ -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),
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Needs param description.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed, thanks.

We really should add a sanity check for that.

};

// returns true if the Guided-mode-option is set (see GUID_OPTIONS)
Expand Down
5 changes: 5 additions & 0 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
18 changes: 18 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 = ([
Expand Down Expand Up @@ -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

Expand Down
Loading