Skip to content

Commit

Permalink
Copter: remove throttle check for arming in guided
Browse files Browse the repository at this point in the history
Co-authored-by: muramura <[email protected]>

.... but add a guided option to put it back.
  • Loading branch information
peterbarker committed Sep 9, 2024
1 parent 82a4bb5 commit f62cc23
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 2 deletions.
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),
};

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

0 comments on commit f62cc23

Please sign in to comment.