Skip to content

Commit

Permalink
Copter: use an enumeration for pre-throw motor state
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed Dec 8, 2020
1 parent bd0dff1 commit f4cbc50
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 4 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -699,7 +699,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
// @Values: 0:Stopped,1:Running
// @User: Standard
GSCALAR(throw_motor_start, "THROW_MOT_START", 0),
GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),
#endif

// @Param: RTL_ALT_TYPE
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -447,7 +447,7 @@ class Parameters {
AP_Int16 gcs_pid_mask;

#if MODE_THROW_ENABLED == ENABLED
AP_Int8 throw_motor_start;
AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;
#endif

AP_Int8 rtl_alt_type;
Expand Down
5 changes: 5 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -1340,6 +1340,11 @@ class ModeThrow : public Mode {
Drop = 1
};

enum class PreThrowMotorState {
STOPPED = 0,
RUNNING = 1,
};

protected:

const char *name() const override { return "THROW"; }
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/mode_throw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ void ModeThrow::run()
case Throw_Disarmed:

// prevent motors from rotating before the throw is detected unless enabled by the user
if (g.throw_motor_start == 1) {
if (g.throw_motor_start == PreThrowMotorState::RUNNING) {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
Expand All @@ -123,7 +123,7 @@ void ModeThrow::run()
case Throw_Detecting:

// prevent motors from rotating before the throw is detected unless enabled by the user
if (g.throw_motor_start == 1) {
if (g.throw_motor_start == PreThrowMotorState::RUNNING) {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
Expand Down

0 comments on commit f4cbc50

Please sign in to comment.