diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 3bcb61b5f0..bf21f092fc 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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 diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index b2335dffb9..463952d5bd 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -447,7 +447,7 @@ public: AP_Int16 gcs_pid_mask; #if MODE_THROW_ENABLED == ENABLED - AP_Int8 throw_motor_start; + AP_Enum throw_motor_start; #endif AP_Int8 rtl_alt_type; diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index c230565b3d..c921812667 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1340,6 +1340,11 @@ public: Drop = 1 }; + enum class PreThrowMotorState { + STOPPED = 0, + RUNNING = 1, + }; + protected: const char *name() const override { return "THROW"; } diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index 6d3e4f49ea..224b38bc27 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -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); @@ -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);